11 #ifndef RDL_DYNAMICS_H 12 #define RDL_DYNAMICS_H 175 bool update_kinematics =
true);
204 #endif // ifndef RDL_DYNAMICS_H void compositeRigidBodyAlgorithm(Model &model, const Math::VectorNd &Q, Math::MatrixNd &H, bool update_kinematics=true)
Computes the joint space inertia matrix by using the Composite Rigid Body Algorithm.
std::vector< SpatialForce, Eigen::aligned_allocator< SpatialForce > > SpatialForceV
void coriolisEffects(Model &model, const Math::VectorNd &Q, const Math::VectorNd &QDot, Math::VectorNd &Tau, bool update_kinematics=true)
Computes the coriolis forces.
LinearSolver
Available solver methods for the linear systems.
void calcBodyGravityWrench(Model &model, unsigned int body_id, RobotDynamics::Math::SpatialForce &gravity_wrench)
Calculate the wrench due to gravity on a body.
void calcMInvTimesTau(Model &model, const Math::VectorNd &Q, const Math::VectorNd &Tau, Math::VectorNd &QDDot, bool update_kinematics=true)
Computes the effect of multiplying the inverse of the joint space inertia matrix with a vector in lin...
A SpatialForce is a spatial vector with the angular part being three moments and the linear part bein...
void gravityEffects(Model &model, Math::VectorNd &Tau)
Computes the gravity vector.
void inverseDynamics(Model &model, const Math::VectorNd &Q, const Math::VectorNd &QDot, const Math::VectorNd &QDDot, Math::VectorNd &Tau, Math::SpatialForceV *f_ext=nullptr, bool update_kinematics=true)
void forwardDynamics(Model &model, const Math::VectorNd &Q, const Math::VectorNd &QDot, const Math::VectorNd &Tau, Math::VectorNd &QDDot, Math::SpatialForceV *f_ext=nullptr, bool update_kinematics=true)
Computes forward dynamics with the Articulated Body Algorithm.
void forwardDynamicsLagrangian(Model &model, const Math::VectorNd &Q, const Math::VectorNd &QDot, const Math::VectorNd &Tau, Math::VectorNd &QDDot, Math::MatrixNd &H, Math::VectorNd &C, Math::LinearSolver linear_solver=Math::LinearSolverColPivHouseholderQR, Math::SpatialForceV *f_ext=nullptr, bool update_kinematics=true)
Computes forward dynamics by building and solving the full Lagrangian equation.
void nonlinearEffects(Model &model, const Math::VectorNd &Q, const Math::VectorNd &QDot, Math::VectorNd &Tau, bool update_kinematics=true)
Computes the coriolis forces.
Namespace for all structures of the RobotDynamics library.