pinocchio  3.3.0
A fast and flexible implementation of Rigid Body Dynamics algorithms and their analytical derivatives
DataTpl< _Scalar, _Options, JointCollectionTpl > Struct Template Reference
Inheritance diagram for DataTpl< _Scalar, _Options, JointCollectionTpl >:
Collaboration diagram for DataTpl< _Scalar, _Options, JointCollectionTpl >:

Public Types

enum  { Options = _Options }
 
typedef Eigen::Matrix< Scalar, 6, 10, Options > BodyRegressorType
 The type of the body regressor.
 
typedef VectorXs ConfigVectorType
 Dense vectorized version of a joint configuration vector.
 
typedef ForceTpl< Scalar, Options > Force
 
typedef FrameTpl< Scalar, Options > Frame
 
typedef pinocchio::FrameIndex FrameIndex
 
typedef pinocchio::GeomIndex GeomIndex
 
typedef pinocchio::Index Index
 
typedef std::vector< Index > IndexVector
 
typedef InertiaTpl< Scalar, Options > Inertia
 
typedef JointCollectionTpl< Scalar, Options > JointCollection
 
typedef JointDataTpl< Scalar, Options, JointCollectionTpl > JointData
 
typedef pinocchio::JointIndex JointIndex
 
typedef JointModelTpl< Scalar, Options, JointCollectionTpl > JointModel
 
typedef Eigen::Matrix< Scalar, 3, Eigen::Dynamic, Options > Matrix3x
 The 3d jacobian type (temporary)
 
typedef Eigen::Matrix< Scalar, 6, 6, Options > Matrix6
 
typedef Eigen::Matrix< Scalar, 6, Eigen::Dynamic, Options > Matrix6x
 The 6d jacobian type (temporary)
 
typedef Eigen::Matrix< Scalar, Eigen::Dynamic, Eigen::Dynamic, Options > MatrixXs
 
typedef ModelTpl< Scalar, Options, JointCollectionTpl > Model
 
typedef MotionTpl< Scalar, Options > Motion
 
typedef Eigen::Matrix< Scalar, 6, 6, Eigen::RowMajor|Options > RowMatrix6
 
typedef Eigen::Matrix< Scalar, Eigen::Dynamic, Eigen::Dynamic, Eigen::RowMajor|Options > RowMatrixXs
 
typedef Eigen::Matrix< Scalar, 1, Eigen::Dynamic, Options|Eigen::RowMajor > RowVectorXs
 
typedef _Scalar Scalar
 
typedef SE3Tpl< Scalar, Options > SE3
 
typedef VectorXs TangentVectorType
 Dense vectorized version of a joint tangent vector (e.g. velocity, acceleration, etc). It also handles the notion of co-tangent vector (e.g. torque, etc).
 
typedef Tensor< Scalar, 3, Options > Tensor3x
   More...
 
typedef Eigen::Matrix< Scalar, 3, 1, Options > Vector3
 
typedef Eigen::Matrix< Scalar, 6, 1, Options > Vector6
 
typedef Eigen::Matrix< Scalar, 6, 1, Options > Vector6c
 
typedef Eigen::Matrix< Scalar, 1, 6, Eigen::RowMajor|Options > Vector6r
 
typedef Eigen::Matrix< Scalar, Eigen::Dynamic, 1, Options > VectorXs
 
- Public Types inherited from NumericalBase< DataTpl< _Scalar, _Options, JointCollectionTpl > >
typedef traits< DataTpl< _Scalar, _Options, JointCollectionTpl > >::Scalar Scalar
 

Public Member Functions

 DataTpl ()
 Default constructor.
 
 DataTpl (const Model &model)
 Default constructor of pinocchio::Data from a pinocchio::Model. More...
 
 PINOCCHIO_ALIGNED_STD_VECTOR (Force) f
 Vector of body forces expressed in the local frame of the joint. For each body, the force represents the sum of all external forces acting on the body.
 
 PINOCCHIO_ALIGNED_STD_VECTOR (Force) h
 Vector of spatial momenta expressed in the local frame of the joint.
 
 PINOCCHIO_ALIGNED_STD_VECTOR (Force) of
 Vector of body forces expressed at the origin of the world. For each body, the force represents the sum of all external forces acting on the body.
 
 PINOCCHIO_ALIGNED_STD_VECTOR (Force) of_augmented
 Vector of body forces expressed in the world frame. For each body, the force represents the sum of all external forces acting on the body. These forces are used in the context of augmented Lagrangian algorithms.
 
 PINOCCHIO_ALIGNED_STD_VECTOR (Force) oh
 Vector of spatial momenta expressed at the origin of the world.
 
 PINOCCHIO_ALIGNED_STD_VECTOR (Inertia) oinertias
 Rigid Body Inertia supported by the joint expressed in the world frame.
 
 PINOCCHIO_ALIGNED_STD_VECTOR (Inertia) oYcrb
 Composite Rigid Body Inertia expressed in the world frame.
 
 PINOCCHIO_ALIGNED_STD_VECTOR (Inertia) Ycrb
 Vector of sub-tree composite rigid body inertias, i.e. the apparent inertia of the subtree supported by the joint and expressed in the local frame of the joint..
 
 PINOCCHIO_ALIGNED_STD_VECTOR (int) const raint_ind
 
 PINOCCHIO_ALIGNED_STD_VECTOR (int) const raints_supported_dim
 
 PINOCCHIO_ALIGNED_STD_VECTOR (int) par_cons_ind
 
typedef PINOCCHIO_ALIGNED_STD_VECTOR (JointData) JointDataVector
 
typedef PINOCCHIO_ALIGNED_STD_VECTOR (JointModel) JointModelVector
 
 PINOCCHIO_ALIGNED_STD_VECTOR (Matrix6) B
 Combined variations of the inertia matrix \( B_i = \frac{1}{2} [(v_i\times∗)I_i + (I_i v_i)\times^{∗} − I_i(v_i\times)] \) consistent with Christoffel symbols.
 
 PINOCCHIO_ALIGNED_STD_VECTOR (Matrix6) doYcrb
 Time variation of Composite Rigid Body Inertia expressed in the world frame.
 
 PINOCCHIO_ALIGNED_STD_VECTOR (Matrix6) dYcrb
 Vector of sub-tree composite rigid body inertia time derivatives \( \dot{Y}_{crb}\). See Data::Ycrb for more details.
 
 PINOCCHIO_ALIGNED_STD_VECTOR (Matrix6) extended_motion_propagator2
 
 PINOCCHIO_ALIGNED_STD_VECTOR (Matrix6) Ivx
 Left variation of the inertia matrix.
 
 PINOCCHIO_ALIGNED_STD_VECTOR (Matrix6) oK
 Inverse articulated inertia.
 
 PINOCCHIO_ALIGNED_STD_VECTOR (Matrix6) oL
 Acceleration propagator.
 
 PINOCCHIO_ALIGNED_STD_VECTOR (Matrix6) oYaba
 Articulated Body Inertia matrix of the subtree expressed in the WORLD coordinate frame.
 
 PINOCCHIO_ALIGNED_STD_VECTOR (Matrix6) spatial_inv_inertia
 
 PINOCCHIO_ALIGNED_STD_VECTOR (Matrix6) vxI
 Right variation of the inertia matrix.
 
 PINOCCHIO_ALIGNED_STD_VECTOR (Matrix6) Yaba
 Articulated Body Inertia matrix of the subtree expressed in the LOCAL coordinate frame of the joint.
 
 PINOCCHIO_ALIGNED_STD_VECTOR (Matrix6x) Fcrb
 Spatial forces set, used in CRBA and CCRBA.
 
 PINOCCHIO_ALIGNED_STD_VECTOR (Matrix6x) KA
 
 PINOCCHIO_ALIGNED_STD_VECTOR (MatrixXs) KAS
 
 PINOCCHIO_ALIGNED_STD_VECTOR (MatrixXs) LA
 
 PINOCCHIO_ALIGNED_STD_VECTOR (Motion) a
 Vector of joint accelerations expressed in the local frame of the joint.
 
 PINOCCHIO_ALIGNED_STD_VECTOR (Motion) a_bias
 
 PINOCCHIO_ALIGNED_STD_VECTOR (Motion) a_gf
 Vector of joint accelerations due to the gravity field.
 
 PINOCCHIO_ALIGNED_STD_VECTOR (Motion) oa
 Vector of joint accelerations expressed at the origin of the world.
 
 PINOCCHIO_ALIGNED_STD_VECTOR (Motion) oa_augmented
 Vector of joint accelerations expressed at the origin of the world. These accelerations are used in the context of augmented Lagrangian algorithms.
 
 PINOCCHIO_ALIGNED_STD_VECTOR (Motion) oa_drift
 Vector of joint accelerations expressed at the origin of the world. These accelerations are used in the context of augmented Lagrangian algorithms.
 
 PINOCCHIO_ALIGNED_STD_VECTOR (Motion) oa_gf
 Vector of joint accelerations expressed at the origin of the world including the gravity contribution.
 
 PINOCCHIO_ALIGNED_STD_VECTOR (Motion) ov
 Vector of joint velocities expressed at the origin of the world.
 
 PINOCCHIO_ALIGNED_STD_VECTOR (Motion) v
 Vector of joint velocities expressed in the local frame of the joint.
 
 PINOCCHIO_ALIGNED_STD_VECTOR (SE3) iMf
 Vector of joint placements wrt to algorithm end effector.
 
 PINOCCHIO_ALIGNED_STD_VECTOR (SE3) liMi
 Vector of relative joint placements (wrt the body parent).
 
 PINOCCHIO_ALIGNED_STD_VECTOR (SE3) oMf
 Vector of absolute operationnel frame placements (wrt the world).
 
 PINOCCHIO_ALIGNED_STD_VECTOR (SE3) oMi
 Vector of absolute joint placements (wrt the world).
 
 PINOCCHIO_ALIGNED_STD_VECTOR (size_t) accumulation_ancestor
 
 PINOCCHIO_ALIGNED_STD_VECTOR (size_t) accumulation_descendant
 
 PINOCCHIO_ALIGNED_STD_VECTOR (size_t) accumulation_joints
 
 PINOCCHIO_ALIGNED_STD_VECTOR (size_t) joints_supporting_constraints
 
 PINOCCHIO_ALIGNED_STD_VECTOR (std::set< size_t >) const raints_supported
 
 PINOCCHIO_ALIGNED_STD_VECTOR (std::vector< size_t >) const raints_on_joint
 
 PINOCCHIO_ALIGNED_STD_VECTOR (Vector3) acom
 Vector of subtree center of mass linear accelerations expressed in the root joint of the subtree. In other words, acom[j] is the CoM linear acceleration of the subtree supported by joint \( j \) and expressed in the joint frame \( j \). The element acom[0] corresponds to the acceleration of the CoM of the whole model expressed in the global frame.
 
 PINOCCHIO_ALIGNED_STD_VECTOR (Vector3) com
 Vector of subtree center of mass positions expressed in the root joint of the subtree. In other words, com[j] is the CoM position of the subtree supported by joint \( j \) and expressed in the joint frame \( j \). The element com[0] corresponds to the center of mass position of the whole model and expressed in the global frame.
 
 PINOCCHIO_ALIGNED_STD_VECTOR (Vector3) vcom
 Vector of subtree center of mass linear velocities expressed in the root joint of the subtree. In other words, vcom[j] is the CoM linear velocity of the subtree supported by joint \( j \) and expressed in the joint frame \( j \). The element vcom[0] corresponds to the velocity of the CoM of the whole model expressed in the global frame.
 
 PINOCCHIO_ALIGNED_STD_VECTOR (VectorXs) lA
 
 PINOCCHIO_ALIGNED_STD_VECTOR (VectorXs) lambdaA
 
- Public Member Functions inherited from Serializable< DataTpl< _Scalar, _Options, JointCollectionTpl > >
void loadFromBinary (boost::asio::streambuf &container)
 Loads a Derived object from a binary container.
 
void loadFromBinary (const std::string &filename)
 Loads a Derived object from an binary file.
 
void loadFromBinary (StaticBuffer &container)
 Loads a Derived object from a static binary container.
 
void loadFromString (const std::string &str)
 Loads a Derived object from a string.
 
void loadFromStringStream (std::istringstream &is)
 Loads a Derived object from a stream string.
 
void loadFromText (const std::string &filename)
 Loads a Derived object from a text file.
 
void loadFromXML (const std::string &filename, const std::string &tag_name)
 Loads a Derived object from an XML file.
 
void saveToBinary (boost::asio::streambuf &container) const
 Saves a Derived object as a binary container.
 
void saveToBinary (const std::string &filename) const
 Saves a Derived object as an binary file.
 
void saveToBinary (StaticBuffer &container) const
 Saves a Derived object as a static binary container.
 
std::string saveToString () const
 Saves a Derived object to a string.
 
void saveToStringStream (std::stringstream &ss) const
 Saves a Derived object to a string stream.
 
void saveToText (const std::string &filename) const
 Saves a Derived object as a text file.
 
void saveToXML (const std::string &filename, const std::string &tag_name) const
 Saves a Derived object as an XML file.
 

Public Attributes

Matrix6x Ag
 Centroidal Momentum Matrix. More...
 
BodyRegressorType bodyRegressor
 Body regressor.
 
MatrixXs C
 The Coriolis matrix (a square matrix of dim model.nv).
 
ContactCholeskyDecomposition contact_chol
 Cholesky decomposition of the KKT contact matrix.
 
PINOCCHIO_COMPILER_DIAGNOSTIC_PUSH PINOCCHIO_COMPILER_DIAGNOSTIC_IGNORED_DEPRECECATED_DECLARATIONS typedef ContactCholeskyDecompositionTpl< Scalar, Options > ContactCholeskyDecomposition
 
VectorXs D
 Diagonal of the joint space intertia matrix obtained by a Cholesky Decomposition.
 
Tensor3x d2tau_dadq
 SO Cross-Partial derivative of the joint torque vector with respect to the joint acceleration/configuration. This also equals to the first-order partial derivative of the Mass Matrix w.r.t joint configuration.
 
Tensor3x d2tau_dqdq
 SO Partial derivative of the joint torque vector with respect to the joint configuration.
 
Tensor3x d2tau_dqdv
 SO Cross-Partial derivative of the joint torque vector with respect to the joint configuration/velocity.
 
Tensor3x d2tau_dvdv
 SO Partial derivative of the joint torque vector with respect to the joint velocity.
 
MatrixXs dac_da
 
MatrixXs dac_dq
 
MatrixXs dac_dv
 
Matrix6x dAdq
 Variation of the spatial acceleration set with respect to the joint configuration.
 
Matrix6x dAdv
 Variation of the spatial acceleration set with respect to the joint velocity.
 
Matrix6x dAg
 Centroidal Momentum Matrix Time Variation. More...
 
Matrix6x ddJ
 Second derivative of the Jacobian with respect to the time.
 
TangentVectorType ddq
 The joint accelerations computed from ABA.
 
RowMatrixXs ddq_dq
 Partial derivative of the joint acceleration vector with respect to the joint configuration.
 
RowMatrixXs ddq_dtau
 Partial derivative of the joint acceleration vector with respect to the joint torques.
 
RowMatrixXs ddq_dv
 Partial derivative of the joint acceleration vector with respect to the joint velocity.
 
Matrix6x dFda
 Variation of the forceset with respect to the joint acceleration.
 
Matrix6x dFdq
 Variation of the forceset with respect to the joint configuration.
 
Matrix6x dFdv
 Variation of the forceset with respect to the joint velocity.
 
Matrix6x dHdq
 Variation of the spatial momenta set with respect to the joint configuration.
 
Force dhg
 Centroidal momentum time derivative. More...
 
VectorXs diff_lambda_c
 Difference between two consecutive iterations of the proxy algorithm.
 
VectorXs Dinv
 Diagonal inverse of the joint space intertia matrix obtained by a Cholesky Decomposition.
 
Matrix6x dJ
 Derivative of the Jacobian with respect to the time.
 
MatrixXs dlambda_dq
 Partial derivatives of the constraints forces with respect to the joint configuration, velocity and torque;.
 
MatrixXs dlambda_dtau
 
MatrixXs dlambda_dv
 
MatrixXs dlambda_dx_prox
 
TangentVectorType dq_after
 Generalized velocity after impact.
 
MatrixXs drhs_prox
 
RowMatrixXs dtau_dq
 Partial derivative of the joint torque vector with respect to the joint configuration.
 
RowMatrixXs dtau_dv
 Partial derivative of the joint torque vector with respect to the joint velocity.
 
MatrixXs dvc_dq
 Stack of partial derivative of the contact frame acceleration with respect to the joint parameters.
 
Matrix6x dVdq
 Variation of the spatial velocity set with respect to the joint configuration.
 
std::vector< int > end_idx_v_fromRow
 End index of the Joint motion subspace.
 
 extended_motion_propagator
 
VectorXs g
 Vector of generalized gravity (dim model.nv). More...
 
Force hg
 Centroidal momentum quantity. More...
 
Inertia Ig
 Centroidal Composite Rigid Body Inertia. More...
 
VectorXs impulse_c
 Lagrange Multipliers corresponding to the contact impulses in pinocchio::impulseDynamics.
 
Matrix6x IS
 Used in computeMinverse.
 
Matrix6 Itmp
 Temporary for derivative algorithms.
 
Matrix6x J
 Jacobian of joint placements. More...
 
Matrix3x Jcom
 Jacobian of center of mass. More...
 
MatrixXs JMinvJt
 Inverse of the operational-space inertia matrix.
 
PINOCCHIO_COMPILER_DIAGNOSTIC_POP JointDataVector joints
 Vector of pinocchio::JointData associated to the pinocchio::JointModel stored in model, encapsulated in JointDataAccessor.
 
MatrixXs jointTorqueRegressor
 Matrix related to joint torque regressor.
 
Tensor3x kinematic_hessians
 Tensor containing the kinematic Hessian of all the joints.
 
Scalar kinetic_energy
 Kinetic energy of the system.
 
RowVectorXs kineticEnergyRegressor
 Matrix related to kinetic energy regressor.
 
VectorXs lambda_c
 Lagrange Multipliers corresponding to the contact forces in pinocchio::forwardDynamics.
 
VectorXs lambda_c_prox
 Proximal Lagrange Multipliers used in the computation of the Forward Dynamics computations.
 
std::vector< int > lastChild
 Index of the last child (for CRBA)
 
Eigen::LLT< MatrixXs > llt_JMinvJt
 Cholesky decompostion of \(JMinvJt\).
 
MatrixXs M
 The joint space inertia matrix (a square matrix of dim model.nv).
 
Matrix6 M6tmp
 Temporary for derivative algorithms.
 
RowMatrix6 M6tmpR
 
RowMatrix6 M6tmpR2
 
std::vector< Scalar > mass
 Vector of subtree mass. In other words, mass[j] is the mass of the subtree supported by joint \( j \). The element mass[0] corresponds to the total mass of the model.
 
Scalar mechanical_energy
 Mechanical energy of the system.
 
RowMatrixXs Minv
 The inverse of the joint space inertia matrix (a square matrix of dim model.nv).
 
VectorXs nle
 Vector of Non Linear Effects (dim model.nv). It corresponds to concatenation of the Coriolis, centrifugal and gravitational effects. More...
 
std::vector< int > nvSubtree
 Dimension of the subtree motion space (for CRBA)
 
std::vector< int > nvSubtree_fromRow
 Subtree of the current row index (used in Cholesky Decomposition).
 
MatrixXs osim
 Operational space inertia matrix;.
 
Eigen::LLT< MatrixXs > osim_llt
 
 oYaba_contact
 Articulated Body Inertia matrix with contact apparent inertia, of a given the subtree and expressed in the WORLD coordinate frame.
 
std::vector< int > parents_fromRow
 First previous non-zero row in M (used in Cholesky Decomposition).
 
Scalar potential_energy
 Potential energy of the system.
 
RowVectorXs potentialEnergyRegressor
 Matrix related to potential energy regressor.
 
VectorXs primal_dual_contact_solution
 RHS vector when solving the contact dynamics KKT problem.
 
VectorXs primal_rhs_contact
 Primal RHS in contact dynamic equations.
 
Matrix6x psid
 psidot Derivative of Jacobian w.r.t to the parent body moving v(p(j)) x Sj
 
Matrix6x psidd
 psiddot Second Derivative of Jacobian w.r.t to the parent body moving a(p(j)) x Sj + v(p(j)) x psidj
 
Matrix6x SDinv
 Used in computeMinverse.
 
MatrixXs sDUiJt
 Temporary corresponding to \( \sqrt{D} U^{-1} J^{\top} \).
 
std::vector< int > start_idx_v_fromRow
 Starting index of the Joint motion subspace.
 
Matrix3x staticRegressor
 Matrix related to static regressor.
 
std::vector< std::vector< int > > supports_fromRow
 Each element of this vector corresponds to the ordered list of indexes belonging to the supporting tree of the given index at the row level. It may be helpful to retrieve the sparsity pattern through it.
 
TangentVectorType tau
 Vector of joint torques (dim model.nv).
 
VectorXs tmp
 Temporary of size NV used in Cholesky Decomposition.
 
VectorXs torque_residual
 Temporary corresponding to the residual torque \( \tau - b(q,\dot{q}) \).
 
TangentVectorType u
 Intermediate quantity corresponding to apparent torque [ABA].
 
MatrixXs U
 Joint space intertia matrix square root (upper trianglular part) computed with a Cholesky Decomposition.
 
Matrix6x UDinv
 Used in computeMinverse.
 

Detailed Description

template<typename _Scalar, int _Options, template< typename, int > class JointCollectionTpl>
struct pinocchio::DataTpl< _Scalar, _Options, JointCollectionTpl >

Definition at line 40 of file data.hpp.

Member Typedef Documentation

◆ Tensor3x

typedef Tensor<Scalar, 3, Options> Tensor3x

 

The type of Tensor for Kinematics and Dynamics second order derivatives

Definition at line 105 of file data.hpp.

Constructor & Destructor Documentation

◆ DataTpl()

DataTpl ( const Model model)
explicit

Default constructor of pinocchio::Data from a pinocchio::Model.

Parameters
[in]modelThe model structure of the rigid body system.

Member Data Documentation

◆ Ag

Centroidal Momentum Matrix.

Note
\( hg = A_g \dot{q}\) maps the joint velocity set to the centroidal momentum.

Definition at line 284 of file data.hpp.

◆ dAg

Matrix6x dAg

Centroidal Momentum Matrix Time Variation.

Note
\( \dot{h_g} = A_g \ddot{q}\ + \dot{A_g}\dot{q}\) maps the joint velocity and acceleration vectors to the time variation of the centroidal momentum.

Definition at line 290 of file data.hpp.

◆ dhg

Force dhg

Centroidal momentum time derivative.

Note
The centroidal momentum time derivative is expressed in the frame centered at the CoM and aligned with the inertial frame (i.e. the world frame).
\( \dot{h_g} = \left( m\ddot{c}, \dot{L}_{g} \right); \). \( \dot{h_g} \) is the stack of the linear momentum variation and the angular momemtum variation.

Definition at line 305 of file data.hpp.

◆ g

VectorXs g

Vector of generalized gravity (dim model.nv).

Note
In the multibody dynamics equation \( M\ddot{q} + c(q, \dot{q}) + g(q) = \tau \), the gravity effect is associated to the \(g\) term.

Definition at line 184 of file data.hpp.

◆ hg

Force hg

Centroidal momentum quantity.

Note
The centroidal momentum is expressed in the frame centered at the CoM and aligned with the inertial frame (i.e. the world frame).
\( h_g = \left( m\dot{c}, L_{g} \right); \). \( h_g \) is the stack of the linear momentum and the angular momemtum vectors.

Definition at line 297 of file data.hpp.

◆ Ig

Inertia Ig

Centroidal Composite Rigid Body Inertia.

Note
\( hg = Ig v_{\text{mean}}\) map a mean velocity to the current centroidal momentum quantity.

Definition at line 310 of file data.hpp.

◆ J

Jacobian of joint placements.

Note
The columns of J corresponds to the basis of the spatial velocities of each joint and expressed at the origin of the inertial frame. In other words, if \( v_{J_{i}} = S_{i} \dot{q}_{i}\) is the relative velocity of the joint i regarding to its parent, then \(J = \begin{bmatrix} ^{0}X_{1} S_{1} & \cdots & ^{0}X_{i} S_{i} & \cdots & ^{0}X_{\text{nj}} S_{\text{nj}} \end{bmatrix} \). This Jacobian has no special meaning. To get the jacobian of a precise joint, you need to call pinocchio::getJointJacobian

Definition at line 360 of file data.hpp.

◆ Jcom

Matrix3x Jcom

Jacobian of center of mass.

Note
This Jacobian maps the joint velocity vector to the velocity of the center of mass, expressed in the inertial frame. In other words, \( v_{\text{CoM}} = J_{\text{CoM}} \dot{q}\).

Definition at line 450 of file data.hpp.

◆ nle

VectorXs nle

Vector of Non Linear Effects (dim model.nv). It corresponds to concatenation of the Coriolis, centrifugal and gravitational effects.

Note
In the multibody dynamics equation \( M\ddot{q} + b(q, \dot{q}) = \tau \), the non linear effects are associated to the term \(b\).

Definition at line 179 of file data.hpp.


The documentation for this struct was generated from the following files: