51 std::vector<Math::SpatialVector> *f_ext = NULL
71 std::vector<Math::SpatialVector> *f_ext = NULL
93 bool update_kinematics =
true
117 std::vector<Math::SpatialVector> *f_ext = NULL
145 std::vector<Math::SpatialVector> *f_ext = NULL,
176 bool update_kinematics=
true
RBDL_DLLAPI void InverseDynamics(Model &model, const Math::VectorNd &Q, const Math::VectorNd &QDot, const Math::VectorNd &QDDot, Math::VectorNd &Tau, std::vector< Math::SpatialVector > *f_ext=NULL)
Computes inverse dynamics with the Newton-Euler Algorithm.
RBDL_DLLAPI 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...
RBDL_DLLAPI void NonlinearEffects(Model &model, const Math::VectorNd &Q, const Math::VectorNd &QDot, Math::VectorNd &Tau, std::vector< Math::SpatialVector > *f_ext=NULL)
Computes the coriolis forces.
RBDL_DLLAPI void ForwardDynamicsLagrangian(Model &model, const Math::VectorNd &Q, const Math::VectorNd &QDot, const Math::VectorNd &Tau, Math::VectorNd &QDDot, Math::LinearSolver linear_solver=Math::LinearSolverColPivHouseholderQR, std::vector< Math::SpatialVector > *f_ext=NULL, Math::MatrixNd *H=NULL, Math::VectorNd *C=NULL)
Computes forward dynamics by building and solving the full Lagrangian equation.
RBDL_DLLAPI void ForwardDynamics(Model &model, const Math::VectorNd &Q, const Math::VectorNd &QDot, const Math::VectorNd &Tau, Math::VectorNd &QDDot, std::vector< Math::SpatialVector > *f_ext=NULL)
Computes forward dynamics with the Articulated Body Algorithm.
RBDL_DLLAPI 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.
LinearSolverColPivHouseholderQR