1#ifndef ROBOTOC_IMPACT_STATE_EQUATION_HPP_
2#define ROBOTOC_IMPACT_STATE_EQUATION_HPP_
28 const Eigen::VectorXd& q_next,
29 const Eigen::VectorXd& v_next,
57 const Eigen::VectorXd& q_prev,
Dynamics and kinematics model of robots. Wraps pinocchio::Model and pinocchio::Data....
Definition: robot.hpp:32
Newton direction of the solution to the optimal control problem split into a time stage.
Definition: split_direction.hpp:20
The KKT matrix split into a time stage.
Definition: split_kkt_matrix.hpp:18
KKT residual split into each time stage.
Definition: split_kkt_residual.hpp:18
Solution to the optimal control problem split into a time stage.
Definition: split_solution.hpp:20
Data for the state equations.
Definition: state_equation_data.hpp:16
Definition: constraint_component_base.hpp:17
void evalImpactStateEquation(const Robot &robot, const SplitSolution &s, const Eigen::VectorXd &q_next, const Eigen::VectorXd &v_next, SplitKKTResidual &kkt_residual)
Computes the residual in the impact state equation.
void correctCostateDirection(StateEquationData &data, SplitDirection &d)
Corrects the costate direction using the Jacobian of the Lie group.
void correctLinearizeImpactStateEquation(const Robot &robot, const SplitSolution &s, const SplitSolution &s_next, StateEquationData &data, SplitKKTMatrix &kkt_matrix, SplitKKTResidual &kkt_residual)
Corrects the linearized state equation using the Jacobian of the Lie group.
void linearizeImpactStateEquation(const Robot &robot, const Eigen::VectorXd &q_prev, const SplitSolution &s, const SplitSolution &s_next, StateEquationData &data, SplitKKTMatrix &kkt_matrix, SplitKKTResidual &kkt_residual)
Linearizes the impact state equation.