robotoc
robotoc - efficient ROBOT Optimal Control solvers
Loading...
Searching...
No Matches
contact_dynamics.hpp
Go to the documentation of this file.
1#ifndef ROBOTOC_CONTACT_DYNAMICS_HPP_
2#define ROBOTOC_CONTACT_DYNAMICS_HPP_
3
4#include <limits>
5
6#include "Eigen/Core"
7
15
16
17namespace robotoc {
18
26void evalContactDynamics(Robot& robot, const ContactStatus& contact_status,
27 const SplitSolution& s, ContactDynamicsData& data);
28
38void linearizeContactDynamics(Robot& robot, const ContactStatus& contact_status,
39 const SplitSolution& s,
41 SplitKKTResidual& kkt_residual);
42
53void condenseContactDynamics(Robot& robot, const ContactStatus& contact_status,
54 const double dt, ContactDynamicsData& data,
55 SplitKKTMatrix& kkt_matrix,
56 SplitKKTResidual& kkt_residual);
57
66
76void expandContactDynamicsDual(const double dt, const double dts,
78 const SplitDirection& d_next, SplitDirection& d);
79
80} // namespace robotoc
81
82#endif // ROBOTOC_CONTACT_DYNAMICS_HPP_
Data used in ContactDynamics.
Definition: contact_dynamics_data.hpp:14
Contact status of robot model.
Definition: contact_status.hpp:32
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 expandContactDynamicsDual(const double dt, const double dts, ContactDynamicsData &data, const SplitDirection &d_next, SplitDirection &d)
Expands the dual variables, i.e., computes the Newton direction of the condensed dual variables (Lagr...
void condenseContactDynamics(Robot &robot, const ContactStatus &contact_status, const double dt, ContactDynamicsData &data, SplitKKTMatrix &kkt_matrix, SplitKKTResidual &kkt_residual)
Condenses the acceleration, contact forces, and Lagrange multipliers.
void evalContactDynamics(Robot &robot, const ContactStatus &contact_status, const SplitSolution &s, ContactDynamicsData &data)
Computes the residual in the contact dynamics constraint.
void linearizeContactDynamics(Robot &robot, const ContactStatus &contact_status, const SplitSolution &s, ContactDynamicsData &data, SplitKKTResidual &kkt_residual)
Computes the residual and derivatives of the contact dynamics constraint and derivatives of it.
void expandContactDynamicsPrimal(const ContactDynamicsData &data, SplitDirection &d)
Expands the primal variables, i.e., computes the Newton direction of the condensed primal variables (...