pinocchio  2.1.3
DataTpl< _Scalar, _Options, JointCollectionTpl > Struct Template Reference
Collaboration diagram for DataTpl< _Scalar, _Options, JointCollectionTpl >:
[legend]

Public Types

enum  { Options = _Options }
 
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 container::aligned_vector< JointDataJointDataVector
 
typedef pinocchio::JointIndex JointIndex
 
typedef JointModelTpl< Scalar, Options, JointCollectionTpl > JointModel
 
typedef container::aligned_vector< JointModelJointModelVector
 
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 _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 Eigen::Matrix< Scalar, 3, 1, Options > Vector3
 
typedef Eigen::Matrix< Scalar, Eigen::Dynamic, 1, Options > VectorXs
 

Public Member Functions

 DataTpl (const Model &model)
 Default constructor of pinocchio::Data from a pinocchio::Model. More...
 

Public Attributes

container::aligned_vector< Motiona
 Vector of joint accelerations expressed at the centers of the joints frames.
 
container::aligned_vector< Motiona_gf
 Vector of joint accelerations due to the gravity field.
 
container::aligned_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.
 
Matrix6x Ag
 Centroidal Momentum Matrix. More...
 
MatrixXs C
 The Coriolis matrix (a square matrix of dim model.nv).
 
container::aligned_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.
 
VectorXs D
 Diagonal of the joint space intertia matrix obtained by a Cholesky Decomposition.
 
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...
 
TangentVectorType ddq
 The joint accelerations computed from ABA.
 
MatrixXs ddq_dq
 Partial derivative of the joint acceleration vector with respect to the joint configuration.
 
MatrixXs 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 with respect to the joint configuration.
 
Force dhg
 Centroidal momentum time derivative. More...
 
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.
 
container::aligned_vector< typename Inertia::Matrix6 > doYcrb
 Time variation of the inertia quantities expressed in the world frame.
 
TangentVectorType dq_after
 Generalized velocity after impact.
 
MatrixXs dtau_dq
 Partial derivative of the joint torque vector with respect to the joint configuration.
 
MatrixXs dtau_dv
 Partial derivative of the joint torque vector with respect to the joint velocity.
 
Matrix6x dVdq
 Variation of the spatial velocity set with respect to the joint configuration.
 
container::aligned_vector< typename Inertia::Matrix6 > dYcrb
 Vector of sub-tree composite rigid body inertia time derivatives \( \dot{Y}_{crb}\). See Data::Ycrb for more details.
 
container::aligned_vector< Forcef
 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.
 
container::aligned_vector< Matrix6xFcrb
 Spatial forces set, used in CRBA and CCRBA.
 
VectorXs g
 Vector of generalized gravity (dim model.nv). More...
 
container::aligned_vector< Forceh
 Vector of spatial momenta expressed in the local frame of the joint.
 
Force hg
 Centroidal momentum quantity. More...
 
Inertia Ig
 Centroidal Composite Rigid Body Inertia. More...
 
container::aligned_vector< SE3iMf
 Vector of joint placements wrt to algorithm end effector.
 
VectorXs impulse_c
 Lagrange Multipliers corresponding to the contact impulses in pinocchio::impulseDynamics.
 
Matrix6x IS
 Used in computeMinverse.
 
Inertia::Matrix6 Itmp
 Temporary for derivative algorithms.
 
container::aligned_vector< typename Inertia::Matrix6 > Ivx
 Left variation of the inertia matrix.
 
Matrix6x J
 Jacobian of joint placements. More...
 
Matrix3x Jcom
 Jacobien of center of mass. More...
 
MatrixXs JMinvJt
 Inverse of the operational-space inertia matrix.
 
JointDataVector joints
 Vector of pinocchio::JointData associated to the pinocchio::JointModel stored in model, encapsulated in JointDataAccessor.
 
Scalar kinetic_energy
 Kinetic energy of the model.
 
VectorXs lambda_c
 Lagrange Multipliers corresponding to the contact forces in pinocchio::forwardDynamics.
 
std::vector< int > lastChild
 Index of the last child (for CRBA)
 
container::aligned_vector< SE3liMi
 Vector of relative joint placements (wrt the body parent).
 
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.
 
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).
 
container::aligned_vector< Motionoa
 Vector of joint accelerations expressed at the origin of the world.
 
container::aligned_vector< Motionoa_gf
 Vector of joint accelerations expressed at the origin of the world including gravity contribution.
 
container::aligned_vector< Forceof
 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.
 
container::aligned_vector< Forceoh
 Vector of spatial momenta expressed in the world frame.
 
container::aligned_vector< SE3oMf
 Vector of absolute operationnel frame placements (wrt the world).
 
container::aligned_vector< SE3oMi
 Vector of absolute joint placements (wrt the world).
 
container::aligned_vector< Motionov
 Vector of joint velocities expressed at the origin.
 
container::aligned_vector< InertiaoYcrb
 Inertia quantities expressed in the world frame.
 
std::vector< int > parents_fromRow
 First previous non-zero row in M (used in Cholesky Decomposition).
 
Scalar potential_energy
 Potential energy of the model.
 
Matrix6x SDinv
 Used in computeMinverse.
 
MatrixXs sDUiJt
 Temporary corresponding to \( \sqrt{D} U^{-1} J^{\top} \).
 
Matrix3x staticRegressor
 
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.
 
container::aligned_vector< Motionv
 Vector of joint velocities expressed at the centers of the joints.
 
container::aligned_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.
 
container::aligned_vector< typename Inertia::Matrix6 > vxI
 Right variation of the inertia matrix.
 
container::aligned_vector< typename Inertia::Matrix6 > Yaba
 Inertia matrix of the subtree expressed as dense matrix [ABA].
 
container::aligned_vector< InertiaYcrb
 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..
 

Detailed Description

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

Definition at line 25 of file data.hpp.

Constructor & Destructor Documentation

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

Centroidal Momentum Matrix.

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

Definition at line 202 of file data.hpp.

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 207 of file data.hpp.

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 219 of file data.hpp.

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 127 of file data.hpp.

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 213 of file data.hpp.

Inertia Ig

Centroidal Composite Rigid Body Inertia.

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

Definition at line 223 of file data.hpp.

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 253 of file data.hpp.

Referenced by pinocchio::jointJacobian().

Matrix3x Jcom

Jacobien 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 296 of file data.hpp.

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 122 of file data.hpp.


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