Commit e46cc889 authored by jcarpent's avatar jcarpent
Browse files

[Doc] Minor correction of the doc for ccrba

parent a261b5b8
......@@ -43,6 +43,24 @@ namespace se3
Data & data,
const Eigen::VectorXd & q);
///
/// \brief Computes the Centroidal Momentum Matrix, the Composite Ridig Body Inertia as well as the centroidal momenta
/// according to the current joint configuration and velocity.
///
///
/// \param[in] model The model structure of the rigid body system.
/// \param[in] data The data structure of the rigid body system.
/// \param[in] q The joint configuration vector (dim model.nq).
/// \param[in] v The joint velocity vector (dim model.nv).
///
/// \return The Centroidal Momentum Matrix Ag.
///
inline const Data::Matrix6x &
ccrba(const Model & model,
Data & data,
const Eigen::VectorXd & q,
const Eigen::VectorXd & v);
///
/// \brief Computes the upper triangular part of the joint space inertia matrix M by
/// using the Composite Rigid Body Algorithm (Chapter 6, Rigid-Body Dynamics Algorithms, R. Featherstone, 2008).
......
......@@ -417,11 +417,11 @@ namespace se3
// CCRBA return quantities
/// \brief Centroidal Momentum Matrix
/// \note \f$ hg = Ag \dot{q}\f$ maps the joint velocity set to the centroidal momentum.
/// \note \f$ hg = A_g \dot{q}\f$ maps the joint velocity set to the centroidal momentum.
Matrix6x Ag;
/// \brief Centroidal momentum quantity.
/// \note The centroidal momentum is expressed in the frame centered at the CoM and aligned with the inertial frame.
/// \note The centroidal momentum is expressed in the frame centered at the CoM and aligned with the inertial frame (i.e. the world frame).
///
Force hg;
......
Supports Markdown
0% or .
You are about to add 0 people to the discussion. Proceed with caution.
Finish editing this message first!
Please register or to comment