|
void | RobotDynamics::calcContactJacobian (Model &model, const Math::VectorNd &Q, const ConstraintSet &CS, Math::MatrixNd &G, bool update_kinematics=true) |
| Computes the Jacobian for the given ConstraintSet. More...
|
|
void | RobotDynamics::calcContactSystemVariables (Model &model, const Math::VectorNd &Q, const Math::VectorNd &QDot, const Math::VectorNd &Tau, ConstraintSet &CS) |
|
void | RobotDynamics::computeContactImpulsesDirect (Model &model, const Math::VectorNd &Q, const Math::VectorNd &QDotMinus, ConstraintSet &CS, Math::VectorNd &QDotPlus) |
| Computes contact gain by constructing and solving the full lagrangian equation. More...
|
|
void | RobotDynamics::computeContactImpulsesNullSpace (Model &model, const Math::VectorNd &Q, const Math::VectorNd &QDotMinus, ConstraintSet &CS, Math::VectorNd &QDotPlus) |
| Resolves contact gain using solveContactSystemNullSpace() More...
|
|
void | RobotDynamics::computeContactImpulsesRangeSpaceSparse (Model &model, const Math::VectorNd &Q, const Math::VectorNd &QDotMinus, ConstraintSet &CS, Math::VectorNd &QDotPlus) |
| Resolves contact gain using solveContactSystemRangeSpaceSparse() More...
|
|
void | RobotDynamics::forwardDynamicsAccelerationDeltas (Model &model, ConstraintSet &CS, VectorNd &QDDot_t, const unsigned int body_id, const SpatialForceV &f_t) |
| Computes the effect of external forces on the generalized accelerations. More...
|
|
void | RobotDynamics::forwardDynamicsApplyConstraintForces (Model &model, const VectorNd &Tau, ConstraintSet &CS, VectorNd &QDDot) |
| Compute only the effects of external forces on the generalized accelerations. More...
|
|
void | RobotDynamics::forwardDynamicsContactsDirect (Model &model, const Math::VectorNd &Q, const Math::VectorNd &QDot, const Math::VectorNd &Tau, ConstraintSet &CS, Math::VectorNd &QDDot) |
| Computes forward dynamics with contact by constructing and solving the full lagrangian equation. More...
|
|
void | RobotDynamics::forwardDynamicsContactsKokkevis (Model &model, const Math::VectorNd &Q, const Math::VectorNd &QDot, const Math::VectorNd &Tau, ConstraintSet &CS, Math::VectorNd &QDDot) |
| Computes forward dynamics that accounts for active contacts in ConstraintSet. More...
|
|
void | RobotDynamics::forwardDynamicsContactsNullSpace (Model &model, const Math::VectorNd &Q, const Math::VectorNd &QDot, const Math::VectorNd &Tau, ConstraintSet &CS, Math::VectorNd &QDDot) |
|
void | RobotDynamics::forwardDynamicsContactsRangeSpaceSparse (Model &model, const Math::VectorNd &Q, const Math::VectorNd &QDot, const Math::VectorNd &Tau, ConstraintSet &CS, Math::VectorNd &QDDot) |
|
void | RobotDynamics::set_zero (std::vector< SpatialVector > &spatial_values) |
|
void | RobotDynamics::solveContactSystemDirect (Math::MatrixNd &H, const Math::MatrixNd &G, const Math::VectorNd &c, const Math::VectorNd &gamma, Math::VectorNd &qddot, Math::VectorNd &lambda, Math::MatrixNd &A, Math::VectorNd &b, Math::VectorNd &x, Math::LinearSolver &linear_solver) |
| Solves the full contact system directly, i.e. simultaneously for contact forces and joint accelerations. More...
|
|
void | RobotDynamics::solveContactSystemNullSpace (Math::MatrixNd &H, const Math::MatrixNd &G, const Math::VectorNd &c, const Math::VectorNd &gamma, Math::VectorNd &qddot, Math::VectorNd &lambda, Math::MatrixNd &Y, Math::MatrixNd &Z, Math::VectorNd &qddot_y, Math::VectorNd &qddot_z, Math::LinearSolver &linear_solver) |
| Solves the contact system by first solving for the joint accelerations and then for the constraint forces. More...
|
|
void | RobotDynamics::solveContactSystemRangeSpaceSparse (Model &model, Math::MatrixNd &H, const Math::MatrixNd &G, const Math::VectorNd &c, const Math::VectorNd &gamma, Math::VectorNd &qddot, Math::VectorNd &lambda, Math::MatrixNd &K, Math::VectorNd &a, Math::LinearSolver linear_solver) |
| Solves the contact system by first solving for the the joint accelerations and then the contact forces using a sparse matrix decomposition of the joint space inertia matrix. More...
|
|