Dynamics.h
Go to the documentation of this file.
1 /*
2  * Original Copyright (c) 2011-2016 Martin Felis <martin.felis@iwr.uni-heidelberg.de>
3  *
4  *
5  * RDL - Robot Dynamics Library
6  * Modifications Copyright (c) 2017 Jordan Lack <jlack1987@gmail.com>
7  *
8  * Licensed under the zlib license. See LICENSE for more details.
9  */
10 
11 #ifndef RDL_DYNAMICS_H
12 #define RDL_DYNAMICS_H
13 
14 #include <assert.h>
15 #include <iostream>
16 
19 
20 namespace RobotDynamics
21 {
22 struct Model;
23 
50 void inverseDynamics(Model& model, const Math::VectorNd& Q, const Math::VectorNd& QDot, const Math::VectorNd& QDDot, Math::VectorNd& Tau,
51  Math::SpatialForceV* f_ext = nullptr, bool update_kinematics = true);
52 
70 void coriolisEffects(Model& model, const Math::VectorNd& Q, const Math::VectorNd& QDot, Math::VectorNd& Tau, bool update_kinematics = true);
71 
83 void gravityEffects(Model& model, Math::VectorNd& Tau);
84 
95 void calcBodyGravityWrench(Model& model, unsigned int body_id, RobotDynamics::Math::SpatialForce& gravity_wrench);
96 
112 void nonlinearEffects(Model& model, const Math::VectorNd& Q, const Math::VectorNd& QDot, Math::VectorNd& Tau, bool update_kinematics = true);
113 
129 void compositeRigidBodyAlgorithm(Model& model, const Math::VectorNd& Q, Math::MatrixNd& H, bool update_kinematics = true);
130 
146 void forwardDynamics(Model& model, const Math::VectorNd& Q, const Math::VectorNd& QDot, const Math::VectorNd& Tau, Math::VectorNd& QDDot,
147  Math::SpatialForceV* f_ext = nullptr, bool update_kinematics = true);
148 
175  bool update_kinematics = true);
176 
198 void calcMInvTimesTau(Model& model, const Math::VectorNd& Q, const Math::VectorNd& Tau, Math::VectorNd& QDDot, bool update_kinematics = true);
199 
201 } // namespace RobotDynamics
202 
203 /* RDL_DYNAMICS_H */
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.
Definition: Dynamics.cc:302
std::vector< SpatialForce, Eigen::aligned_allocator< SpatialForce > > SpatialForceV
VectorNd Tau
VectorNd QDDot
VectorNd QDot
void coriolisEffects(Model &model, const Math::VectorNd &Q, const Math::VectorNd &QDot, Math::VectorNd &Tau, bool update_kinematics=true)
Computes the coriolis forces.
Definition: Dynamics.cc:141
VectorNd Q
LinearSolver
Available solver methods for the linear systems.
Definition: rdl_mathutils.h:34
void calcBodyGravityWrench(Model &model, unsigned int body_id, RobotDynamics::Math::SpatialForce &gravity_wrench)
Calculate the wrench due to gravity on a body.
Definition: Dynamics.cc:207
Eigen::VectorXd VectorNd
Definition: rdl_eigenmath.h:25
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...
Definition: Dynamics.cc:596
Eigen::MatrixXd MatrixNd
Definition: rdl_eigenmath.h:26
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.
Definition: Dynamics.cc:100
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)
Definition: Dynamics.cc:23
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.
Definition: Dynamics.cc:455
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.
Definition: Dynamics.cc:579
void nonlinearEffects(Model &model, const Math::VectorNd &Q, const Math::VectorNd &QDot, Math::VectorNd &Tau, bool update_kinematics=true)
Computes the coriolis forces.
Definition: Dynamics.cc:236
Namespace for all structures of the RobotDynamics library.
Definition: Body.h:21


rdl_dynamics
Author(s):
autogenerated on Tue Apr 20 2021 02:25:27