Robot Dynamics Library
|
Functions | |
void | RobotDynamics::inverseDynamics (Model &model, const VectorNd &Q, const VectorNd &QDot, const VectorNd &QDDot, VectorNd &Tau, SpatialForceV *f_ext, bool update_kinematics) |
void | RobotDynamics::coriolisEffects (Model &model, const Math::VectorNd &Q, const Math::VectorNd &QDot, Math::VectorNd &Tau, bool update_kinematics=true) |
Computes the coriolis forces. More... | |
void | RobotDynamics::gravityEffects (Model &model, Math::VectorNd &Tau) |
Computes the gravity vector. More... | |
void | RobotDynamics::calcBodyGravityWrench (Model &model, unsigned int body_id, RobotDynamics::Math::SpatialForce &gravity_wrench) |
Calculate the wrench due to gravity on a body. More... | |
void | RobotDynamics::nonlinearEffects (Model &model, const Math::VectorNd &Q, const Math::VectorNd &QDot, Math::VectorNd &Tau, bool update_kinematics=true) |
Computes the coriolis forces. More... | |
void | RobotDynamics::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. More... | |
void | RobotDynamics::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. More... | |
void | RobotDynamics::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. More... | |
void | RobotDynamics::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 linear time. More... | |
void RobotDynamics::calcBodyGravityWrench | ( | Model & | model, |
unsigned int | body_id, | ||
RobotDynamics::Math::SpatialForce & | gravity_wrench | ||
) |
Calculate the wrench due to gravity on a body.
model | RDL model |
body_id | Wrench will be of this body |
gravity_wrench | Wrench due to gravity on body body_id. Modified |
void RobotDynamics::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 linear time.
model | rigid body model |
Q | state vector of the generalized positions |
Tau | the vector that should be multiplied with the inverse of the joint space inertia matrix |
QDDot | vector where the result will be stored |
update_kinematics | whether the kinematics should be computed. |
This function uses a reduced version of the Articulated Body Algorithm to compute
in ) time.
void RobotDynamics::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.
This function computes the joint space inertia matrix from a given model and the generalized state vector:
model | rigid body model |
Q | state vector of the model |
H | a matrix where the result will be stored in |
update_kinematics | whether the kinematics should be updated (safer, but at a higher computational cost!) |
void RobotDynamics::coriolisEffects | ( | Model & | model, |
const Math::VectorNd & | Q, | ||
const Math::VectorNd & | QDot, | ||
Math::VectorNd & | Tau, | ||
bool | update_kinematics = true |
||
) |
Computes the coriolis forces.
This function computes the generalized forces from given generalized states, and velocities from coriolis effects
model | rigid body model |
Q | state vector of the internal joints |
QDot | velocity vector of the internal joints |
Tau | actuations of the internal joints (output) |
update_kinematics | whether the kinematics should be updated (safer, but at a higher computational cost!) |
void RobotDynamics::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.
This function computes the generalized accelerations from given generalized states, velocities and forces: It does this by using the recursive Articulated Body Algorithm that runs in
with
being the number of joints.
model | rigid body model |
Q | state vector of the internal joints |
QDot | velocity vector of the internal joints |
Tau | actuations of the internal joints |
QDDot | accelerations of the internal joints (output) |
f_ext | External forces acting on the body (optional, defaults to NULL) |
update_kinematics | If true, compute kinematics. Default true |
void RobotDynamics::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.
This method builds and solves the linear system
for where
is the joint space inertia matrix computed with the CompositeRigidBodyAlgorithm(),
the bias force (sometimes called "non-linear effects").
model | rigid body model |
Q | state vector of the internal joints |
QDot | velocity vector of the internal joints |
Tau | actuations of the internal joints |
QDDot | accelerations of the internal joints (output) |
linear_solver | specification which method should be used for solving the linear system |
f_ext | External forces acting on the body (optional, defaults to NULL) |
H | joint space inertia matrix of size dof_count x dof_count. Modified |
C | right hand side vector of size dof_count x 1. Modified |
update_kinematics | whether or not to calculate kinematics. Defaults to true which will compute kinematic quatities |
void RobotDynamics::gravityEffects | ( | Model & | model, |
Math::VectorNd & | Tau | ||
) |
Computes the gravity vector.
This function computes the gravity vector for an RDL model
model | rigid body model |
Tau | Gravity vector. Modified |
void RobotDynamics::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 |
||
) |
@brief Computes inverse dynamics with the Newton-Euler Algorithm
This function computes the generalized forces from given generalized states, velocities, and accelerations:
model | rigid body model |
Q | state vector of the internal joints |
QDot | velocity vector of the internal joints |
QDDot | accelerations of the internals joints |
Tau | actuations of the internal joints (output) |
f_ext | External forces acting on the body (optional, defaults to nullptr) |
update_kinematics | whether or not to calculate kinematics. Defaults to true which will compute kinematic quatities |
void RobotDynamics::nonlinearEffects | ( | Model & | model, |
const Math::VectorNd & | Q, | ||
const Math::VectorNd & | QDot, | ||
Math::VectorNd & | Tau, | ||
bool | update_kinematics = true |
||
) |
Computes the coriolis forces.
This function computes the generalized forces from given generalized states, velocities, and accelerations:
model | rigid body model |
Q | state vector of the internal joints |
QDot | velocity vector of the internal joints |
Tau | actuations of the internal joints (output) |
update_kinematics | whether or not to calculate kinematics. Defaults to true which will compute kinematic quatities |