robotoc
robotoc - efficient ROBOT Optimal Control solvers
Loading...
Searching...
No Matches
impact_dynamics.hpp
Go to the documentation of this file.
1#ifndef ROBOTOC_IMPACT_DYNAMICS_HPP_
2#define ROBOTOC_IMPACT_DYNAMICS_HPP_
3
4#include "Eigen/Core"
5
13
14
15namespace robotoc {
16
24void evalImpactDynamics(Robot& robot, const ImpactStatus& impact_status,
25 const SplitSolution& s, ContactDynamicsData& data);
26
35void linearizeImpactDynamics(Robot& robot, const ImpactStatus& impact_status,
36 const SplitSolution& s, ContactDynamicsData& data,
37 SplitKKTResidual& kkt_residual);
38
47void condenseImpactDynamics(Robot& robot, const ImpactStatus& impact_status,
49 SplitKKTMatrix& kkt_matrix,
50 SplitKKTResidual& kkt_residual);
51
61
71 const SplitDirection& d_next, SplitDirection& d);
72
73} // namespace robotoc
74
75#endif // ROBOTOC_IMPACT_DYNAMICS_HPP_
Data used in ContactDynamics.
Definition: contact_dynamics_data.hpp:14
Impact status of robot model. Wrapper of ContactStatus to treat impacts.
Definition: impact_status.hpp:21
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
Definition: constraint_component_base.hpp:17
void condenseImpactDynamics(Robot &robot, const ImpactStatus &impact_status, ContactDynamicsData &data, SplitKKTMatrix &kkt_matrix, SplitKKTResidual &kkt_residual)
Condenses the inverse dynamics constraint.
void expandImpactDynamicsPrimal(const ContactDynamicsData &data, SplitDirection &d)
Expands the primal variables, i.e., computes the Newton direction of the condensed primal variables (...
void linearizeImpactDynamics(Robot &robot, const ImpactStatus &impact_status, const SplitSolution &s, ContactDynamicsData &data, SplitKKTResidual &kkt_residual)
Linearizes the impact dynamics constraint.
void evalImpactDynamics(Robot &robot, const ImpactStatus &impact_status, const SplitSolution &s, ContactDynamicsData &data)
Computes the residual in the impact dynamics constraint.
void expandImpactDynamicsDual(ContactDynamicsData &data, const SplitDirection &d_next, SplitDirection &d)
Expands the dual variables, i.e., computes the Newton direction of the condensed dual variables (Lagr...