Public Types | Public Member Functions | Public Attributes | Private Member Functions | List of all members
pinocchio::DataTpl< _Scalar, _Options, JointCollectionTpl > Struct Template Reference

#include <data.hpp>

Inheritance diagram for pinocchio::DataTpl< _Scalar, _Options, JointCollectionTpl >:
Inheritance graph
[legend]

Public Types

enum  { Options = _Options }
 
typedef Eigen::Matrix< Scalar, 6, 10, OptionsBodyRegressorType
 The type of the body regressor. More...
 
typedef VectorXs ConfigVectorType
 Dense vectorized version of a joint configuration vector. More...
 
typedef ForceTpl< Scalar, OptionsForce
 
typedef FrameTpl< Scalar, OptionsFrame
 
typedef pinocchio::FrameIndex FrameIndex
 
typedef pinocchio::GeomIndex GeomIndex
 
typedef pinocchio::Index Index
 
typedef std::vector< IndexIndexVector
 
typedef InertiaTpl< Scalar, OptionsInertia
 
typedef JointCollectionTpl< Scalar, OptionsJointCollection
 
typedef JointDataTpl< Scalar, Options, JointCollectionTpl > JointData
 
typedef pinocchio::JointIndex JointIndex
 
typedef JointModelTpl< Scalar, Options, JointCollectionTpl > JointModel
 
typedef Eigen::Matrix< Scalar, 3, Eigen::Dynamic, OptionsMatrix3x
 The 3d jacobian type (temporary) More...
 
typedef Eigen::Matrix< Scalar, 6, 6, OptionsMatrix6
 
typedef Eigen::Matrix< Scalar, 6, Eigen::Dynamic, OptionsMatrix6x
 The 6d jacobian type (temporary) More...
 
typedef Eigen::Matrix< Scalar, Eigen::Dynamic, Eigen::Dynamic, OptionsMatrixXs
 
typedef ModelTpl< Scalar, Options, JointCollectionTpl > Model
 
typedef MotionTpl< Scalar, OptionsMotion
 
typedef Eigen::Matrix< Scalar, 6, 6, Eigen::RowMajor|OptionsRowMatrix6
 
typedef Eigen::Matrix< Scalar, Eigen::Dynamic, Eigen::Dynamic, Eigen::RowMajor|OptionsRowMatrixXs
 
typedef SE3Tpl< Scalar, OptionsSE3
 
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). More...
 
typedef Tensor< Scalar, 3, OptionsTensor3x
   More...
 
typedef Eigen::Matrix< Scalar, 3, 1, OptionsVector3
 
typedef Eigen::Matrix< Scalar, 6, 1, OptionsVector6c
 
typedef Eigen::Matrix< Scalar, 1, 6, Eigen::RowMajor|OptionsVector6r
 
typedef Eigen::Matrix< Scalar, Eigen::Dynamic, 1, OptionsVectorXs
 

Public Member Functions

 DataTpl ()
 Default constructor. More...
 
 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. More...
 
 PINOCCHIO_ALIGNED_STD_VECTOR (Force) h
 Vector of spatial momenta expressed in the local frame of the joint. More...
 
 PINOCCHIO_ALIGNED_STD_VECTOR (Force) of
 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. More...
 
 PINOCCHIO_ALIGNED_STD_VECTOR (Force) oh
 Vector of spatial momenta expressed in the world frame. More...
 
 PINOCCHIO_ALIGNED_STD_VECTOR (Inertia) oinertias
 Rigid Body Inertia supported by the joint expressed in the world frame. More...
 
 PINOCCHIO_ALIGNED_STD_VECTOR (Inertia) oYcrb
 Composite Rigid Body Inertia expressed in the world frame. More...
 
 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.. More...
 
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. More...
 
 PINOCCHIO_ALIGNED_STD_VECTOR (Matrix6) doYcrb
 Time variation of Composite Rigid Body Inertia expressed in the world frame. More...
 
 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. More...
 
 PINOCCHIO_ALIGNED_STD_VECTOR (Matrix6) Ivx
 Left variation of the inertia matrix. More...
 
 PINOCCHIO_ALIGNED_STD_VECTOR (Matrix6) vxI
 Right variation of the inertia matrix. More...
 
 PINOCCHIO_ALIGNED_STD_VECTOR (Matrix6) Yaba
 Inertia matrix of the subtree expressed as dense matrix [ABA]. More...
 
 PINOCCHIO_ALIGNED_STD_VECTOR (Matrix6x) Fcrb
 Spatial forces set, used in CRBA and CCRBA. More...
 
 PINOCCHIO_ALIGNED_STD_VECTOR (Motion) a
 Vector of joint accelerations expressed at the centers of the joints frames. More...
 
 PINOCCHIO_ALIGNED_STD_VECTOR (Motion) a_gf
 Vector of joint accelerations due to the gravity field. More...
 
 PINOCCHIO_ALIGNED_STD_VECTOR (Motion) oa
 Vector of joint accelerations expressed at the origin of the world. More...
 
 PINOCCHIO_ALIGNED_STD_VECTOR (Motion) oa_gf
 Vector of joint accelerations expressed at the origin of the world including gravity contribution. More...
 
 PINOCCHIO_ALIGNED_STD_VECTOR (Motion) ov
 Vector of joint velocities expressed at the origin. More...
 
 PINOCCHIO_ALIGNED_STD_VECTOR (Motion) v
 Vector of joint velocities expressed at the centers of the joints. More...
 
 PINOCCHIO_ALIGNED_STD_VECTOR (SE3) iMf
 Vector of joint placements wrt to algorithm end effector. More...
 
 PINOCCHIO_ALIGNED_STD_VECTOR (SE3) liMi
 Vector of relative joint placements (wrt the body parent). More...
 
 PINOCCHIO_ALIGNED_STD_VECTOR (SE3) oMf
 Vector of absolute operationnel frame placements (wrt the world). More...
 
 PINOCCHIO_ALIGNED_STD_VECTOR (SE3) oMi
 Vector of absolute joint placements (wrt the world). More...
 
 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. More...
 
 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. More...
 
 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. More...
 
- Public Member Functions inherited from pinocchio::serialization::Serializable< DataTpl< _Scalar, _Options, JointCollectionTpl > >
void loadFromBinary (boost::asio::streambuf &container)
 Loads a Derived object from a binary container. More...
 
void loadFromBinary (const std::string &filename)
 Loads a Derived object from an binary file. More...
 
void loadFromBinary (StaticBuffer &container)
 Loads a Derived object from a static binary container. More...
 
void loadFromString (const std::string &str)
 Loads a Derived object from a string. More...
 
void loadFromStringStream (std::istringstream &is)
 Loads a Derived object from a stream string. More...
 
void loadFromText (const std::string &filename)
 Loads a Derived object from a text file. More...
 
void loadFromXML (const std::string &filename, const std::string &tag_name)
 Loads a Derived object from an XML file. More...
 
void saveToBinary (boost::asio::streambuf &container) const
 Saves a Derived object as a binary container. More...
 
void saveToBinary (const std::string &filename) const
 Saves a Derived object as an binary file. More...
 
void saveToBinary (StaticBuffer &container) const
 Saves a Derived object as a static binary container. More...
 
std::string saveToString () const
 Saves a Derived object to a string. More...
 
void saveToStringStream (std::stringstream &ss) const
 Saves a Derived object to a string stream. More...
 
void saveToText (const std::string &filename) const
 Saves a Derived object as a text file. More...
 
void saveToXML (const std::string &filename, const std::string &tag_name) const
 Saves a Derived object as an XML file. More...
 

Public Attributes

Matrix6x Ag
 Centroidal Momentum Matrix. More...
 
BodyRegressorType bodyRegressor
 Body regressor. More...
 
MatrixXs C
 The Coriolis matrix (a square matrix of dim model.nv). More...
 
VectorXs D
 Diagonal of the joint space intertia matrix obtained by a Cholesky Decomposition. More...
 
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. More...
 
Tensor3x d2tau_dqdq
 SO Partial derivative of the joint torque vector with respect to the joint configuration. More...
 
Tensor3x d2tau_dqdv
 SO Cross-Partial derivative of the joint torque vector with respect to the joint configuration/velocity. More...
 
Tensor3x d2tau_dvdv
 SO Partial derivative of the joint torque vector with respect to the joint velocity. More...
 
Matrix6x dAdq
 Variation of the spatial acceleration set with respect to the joint configuration. More...
 
Matrix6x dAdv
 Variation of the spatial acceleration set with respect to the joint velocity. More...
 
Matrix6x dAg
 Centroidal Momentum Matrix Time Variation. More...
 
Matrix6x ddJ
 Second derivative of the Jacobian with respect to the time. More...
 
TangentVectorType ddq
 The joint accelerations computed from ABA. More...
 
MatrixXs ddq_dq
 Partial derivative of the joint acceleration vector with respect to the joint configuration. More...
 
MatrixXs ddq_dv
 Partial derivative of the joint acceleration vector with respect to the joint velocity. More...
 
Matrix6x dFda
 Variation of the forceset with respect to the joint acceleration. More...
 
Matrix6x dFdq
 Variation of the forceset with respect to the joint configuration. More...
 
Matrix6x dFdv
 Variation of the forceset with respect to the joint velocity. More...
 
Matrix6x dHdq
 Variation of the spatial momenta with respect to the joint configuration. More...
 
Force dhg
 Centroidal momentum time derivative. More...
 
VectorXs Dinv
 Diagonal inverse of the joint space intertia matrix obtained by a Cholesky Decomposition. More...
 
Matrix6x dJ
 Derivative of the Jacobian with respect to the time. More...
 
TangentVectorType dq_after
 Generalized velocity after impact. More...
 
MatrixXs dtau_dq
 Partial derivative of the joint torque vector with respect to the joint configuration. More...
 
MatrixXs dtau_dv
 Partial derivative of the joint torque vector with respect to the joint velocity. More...
 
Matrix6x dVdq
 Variation of the spatial velocity set with respect to the joint configuration. More...
 
std::vector< int > end_idx_v_fromRow
 End index of the Joint motion subspace. More...
 
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. More...
 
Matrix6x IS
 Used in computeMinverse. More...
 
Matrix6 Itmp
 Temporary for derivative algorithms. More...
 
Matrix6x J
 Jacobian of joint placements. More...
 
Matrix3x Jcom
 Jacobian of center of mass. More...
 
MatrixXs JMinvJt
 Inverse of the operational-space inertia matrix. More...
 
JointDataVector joints
 Vector of pinocchio::JointData associated to the pinocchio::JointModel stored in model, encapsulated in JointDataAccessor. More...
 
MatrixXs jointTorqueRegressor
 Matrix related to joint torque regressor. More...
 
Tensor3x kinematic_hessians
 Tensor containing the kinematic Hessian of all the joints. More...
 
Scalar kinetic_energy
 Kinetic energy of the model. More...
 
VectorXs lambda_c
 Lagrange Multipliers corresponding to the contact forces in pinocchio::forwardDynamics. More...
 
std::vector< int > lastChild
 Index of the last child (for CRBA) More...
 
Eigen::LLT< MatrixXsllt_JMinvJt
 Cholesky decompostion of $JMinvJt$. More...
 
MatrixXs M
 The joint space inertia matrix (a square matrix of dim model.nv). More...
 
Matrix6 M6tmp
 Temporary for derivative algorithms. More...
 
RowMatrix6 M6tmpR
 
RowMatrix6 M6tmpR2
 
std::vector< Scalarmass
 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. More...
 
RowMatrixXs Minv
 The inverse of the joint space inertia matrix (a square matrix of dim model.nv). More...
 
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) More...
 
std::vector< int > nvSubtree_fromRow
 Subtree of the current row index (used in Cholesky Decomposition). More...
 
std::vector< int > parents_fromRow
 First previous non-zero row in M (used in Cholesky Decomposition). More...
 
Scalar potential_energy
 Potential energy of the model. More...
 
Matrix6x psid
 psidot Derivative of Jacobian w.r.t to the parent body moving v(p(j)) x Sj More...
 
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 More...
 
EIGEN_MAKE_ALIGNED_OPERATOR_NEW typedef _Scalar Scalar
 
Matrix6x SDinv
 Used in computeMinverse. More...
 
MatrixXs sDUiJt
 Temporary corresponding to $ \sqrt{D} U^{-1} J^{\top} $. More...
 
std::vector< int > start_idx_v_fromRow
 Starting index of the Joint motion subspace. More...
 
Matrix3x staticRegressor
 Matrix related to static regressor. More...
 
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. More...
 
TangentVectorType tau
 Vector of joint torques (dim model.nv). More...
 
VectorXs tmp
 Temporary of size NV used in Cholesky Decomposition. More...
 
VectorXs torque_residual
 Temporary corresponding to the residual torque $ \tau - b(q,\dot{q}) $. More...
 
TangentVectorType u
 Intermediate quantity corresponding to apparent torque [ABA]. More...
 
MatrixXs U
 Joint space intertia matrix square root (upper trianglular part) computed with a Cholesky Decomposition. More...
 
Matrix6x UDinv
 Used in computeMinverse. More...
 

Private Member Functions

void computeLastChild (const Model &model)
 
void computeParents_fromRow (const Model &model)
 
void computeSupports_fromRow (const Model &model)
 

Detailed Description

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

Definition at line 29 of file multibody/data.hpp.

Member Typedef Documentation

◆ BodyRegressorType

template<typename _Scalar , int _Options, template< typename, int > class JointCollectionTpl>
typedef Eigen::Matrix<Scalar,6,10,Options> pinocchio::DataTpl< _Scalar, _Options, JointCollectionTpl >::BodyRegressorType

The type of the body regressor.

Definition at line 82 of file multibody/data.hpp.

◆ ConfigVectorType

template<typename _Scalar , int _Options, template< typename, int > class JointCollectionTpl>
typedef VectorXs pinocchio::DataTpl< _Scalar, _Options, JointCollectionTpl >::ConfigVectorType

Dense vectorized version of a joint configuration vector.

Definition at line 66 of file multibody/data.hpp.

◆ Force

template<typename _Scalar , int _Options, template< typename, int > class JointCollectionTpl>
typedef ForceTpl<Scalar,Options> pinocchio::DataTpl< _Scalar, _Options, JointCollectionTpl >::Force

Definition at line 43 of file multibody/data.hpp.

◆ Frame

template<typename _Scalar , int _Options, template< typename, int > class JointCollectionTpl>
typedef FrameTpl<Scalar,Options> pinocchio::DataTpl< _Scalar, _Options, JointCollectionTpl >::Frame

Definition at line 45 of file multibody/data.hpp.

◆ FrameIndex

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

Definition at line 50 of file multibody/data.hpp.

◆ GeomIndex

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

Definition at line 49 of file multibody/data.hpp.

◆ Index

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

Definition at line 47 of file multibody/data.hpp.

◆ IndexVector

template<typename _Scalar , int _Options, template< typename, int > class JointCollectionTpl>
typedef std::vector<Index> pinocchio::DataTpl< _Scalar, _Options, JointCollectionTpl >::IndexVector

Definition at line 51 of file multibody/data.hpp.

◆ Inertia

template<typename _Scalar , int _Options, template< typename, int > class JointCollectionTpl>
typedef InertiaTpl<Scalar,Options> pinocchio::DataTpl< _Scalar, _Options, JointCollectionTpl >::Inertia

Definition at line 44 of file multibody/data.hpp.

◆ JointCollection

template<typename _Scalar , int _Options, template< typename, int > class JointCollectionTpl>
typedef JointCollectionTpl<Scalar,Options> pinocchio::DataTpl< _Scalar, _Options, JointCollectionTpl >::JointCollection

Definition at line 37 of file multibody/data.hpp.

◆ JointData

template<typename _Scalar , int _Options, template< typename, int > class JointCollectionTpl>
typedef JointDataTpl<Scalar,Options,JointCollectionTpl> pinocchio::DataTpl< _Scalar, _Options, JointCollectionTpl >::JointData

Definition at line 54 of file multibody/data.hpp.

◆ JointIndex

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

Definition at line 48 of file multibody/data.hpp.

◆ JointModel

template<typename _Scalar , int _Options, template< typename, int > class JointCollectionTpl>
typedef JointModelTpl<Scalar,Options,JointCollectionTpl> pinocchio::DataTpl< _Scalar, _Options, JointCollectionTpl >::JointModel

Definition at line 53 of file multibody/data.hpp.

◆ Matrix3x

template<typename _Scalar , int _Options, template< typename, int > class JointCollectionTpl>
typedef Eigen::Matrix<Scalar,3,Eigen::Dynamic,Options> pinocchio::DataTpl< _Scalar, _Options, JointCollectionTpl >::Matrix3x

The 3d jacobian type (temporary)

Definition at line 75 of file multibody/data.hpp.

◆ Matrix6

template<typename _Scalar , int _Options, template< typename, int > class JointCollectionTpl>
typedef Eigen::Matrix<Scalar,6,6,Options> pinocchio::DataTpl< _Scalar, _Options, JointCollectionTpl >::Matrix6

Definition at line 77 of file multibody/data.hpp.

◆ Matrix6x

template<typename _Scalar , int _Options, template< typename, int > class JointCollectionTpl>
typedef Eigen::Matrix<Scalar,6,Eigen::Dynamic,Options> pinocchio::DataTpl< _Scalar, _Options, JointCollectionTpl >::Matrix6x

The 6d jacobian type (temporary)

Definition at line 73 of file multibody/data.hpp.

◆ MatrixXs

template<typename _Scalar , int _Options, template< typename, int > class JointCollectionTpl>
typedef Eigen::Matrix<Scalar,Eigen::Dynamic,Eigen::Dynamic,Options> pinocchio::DataTpl< _Scalar, _Options, JointCollectionTpl >::MatrixXs

Definition at line 59 of file multibody/data.hpp.

◆ Model

template<typename _Scalar , int _Options, template< typename, int > class JointCollectionTpl>
typedef ModelTpl<Scalar,Options,JointCollectionTpl> pinocchio::DataTpl< _Scalar, _Options, JointCollectionTpl >::Model

Definition at line 39 of file multibody/data.hpp.

◆ Motion

template<typename _Scalar , int _Options, template< typename, int > class JointCollectionTpl>
typedef MotionTpl<Scalar,Options> pinocchio::DataTpl< _Scalar, _Options, JointCollectionTpl >::Motion

Definition at line 42 of file multibody/data.hpp.

◆ RowMatrix6

template<typename _Scalar , int _Options, template< typename, int > class JointCollectionTpl>
typedef Eigen::Matrix<Scalar,6,6,Eigen::RowMajor | Options> pinocchio::DataTpl< _Scalar, _Options, JointCollectionTpl >::RowMatrix6

Definition at line 78 of file multibody/data.hpp.

◆ RowMatrixXs

template<typename _Scalar , int _Options, template< typename, int > class JointCollectionTpl>
typedef Eigen::Matrix<Scalar,Eigen::Dynamic,Eigen::Dynamic,Eigen::RowMajor | Options> pinocchio::DataTpl< _Scalar, _Options, JointCollectionTpl >::RowMatrixXs

Definition at line 79 of file multibody/data.hpp.

◆ SE3

template<typename _Scalar , int _Options, template< typename, int > class JointCollectionTpl>
typedef SE3Tpl<Scalar,Options> pinocchio::DataTpl< _Scalar, _Options, JointCollectionTpl >::SE3

Definition at line 41 of file multibody/data.hpp.

◆ TangentVectorType

template<typename _Scalar , int _Options, template< typename, int > class JointCollectionTpl>
typedef VectorXs pinocchio::DataTpl< _Scalar, _Options, JointCollectionTpl >::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).

Definition at line 70 of file multibody/data.hpp.

◆ Tensor3x

template<typename _Scalar , int _Options, template< typename, int > class JointCollectionTpl>
typedef Tensor<Scalar,3,Options> pinocchio::DataTpl< _Scalar, _Options, JointCollectionTpl >::Tensor3x

 

The type of Tensor for Kinematics and Dynamics second order derivatives

Definition at line 85 of file multibody/data.hpp.

◆ Vector3

template<typename _Scalar , int _Options, template< typename, int > class JointCollectionTpl>
typedef Eigen::Matrix<Scalar,3,1,Options> pinocchio::DataTpl< _Scalar, _Options, JointCollectionTpl >::Vector3

Definition at line 61 of file multibody/data.hpp.

◆ Vector6c

template<typename _Scalar , int _Options, template< typename, int > class JointCollectionTpl>
typedef Eigen::Matrix<Scalar, 6, 1, Options> pinocchio::DataTpl< _Scalar, _Options, JointCollectionTpl >::Vector6c

Definition at line 62 of file multibody/data.hpp.

◆ Vector6r

template<typename _Scalar , int _Options, template< typename, int > class JointCollectionTpl>
typedef Eigen::Matrix<Scalar, 1, 6, Eigen::RowMajor | Options> pinocchio::DataTpl< _Scalar, _Options, JointCollectionTpl >::Vector6r

Definition at line 63 of file multibody/data.hpp.

◆ VectorXs

template<typename _Scalar , int _Options, template< typename, int > class JointCollectionTpl>
typedef Eigen::Matrix<Scalar,Eigen::Dynamic,1,Options> pinocchio::DataTpl< _Scalar, _Options, JointCollectionTpl >::VectorXs

Definition at line 60 of file multibody/data.hpp.

Member Enumeration Documentation

◆ anonymous enum

template<typename _Scalar , int _Options, template< typename, int > class JointCollectionTpl>
anonymous enum
Enumerator
Options 

Definition at line 35 of file multibody/data.hpp.

Constructor & Destructor Documentation

◆ DataTpl() [1/2]

template<typename _Scalar , int _Options, template< typename, int > class JointCollectionTpl>
pinocchio::DataTpl< _Scalar, _Options, JointCollectionTpl >::DataTpl ( const Model model)
explicit

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

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

◆ DataTpl() [2/2]

template<typename _Scalar , int _Options, template< typename, int > class JointCollectionTpl>
pinocchio::DataTpl< _Scalar, _Options, JointCollectionTpl >::DataTpl ( )
inline

Default constructor.

Definition at line 408 of file multibody/data.hpp.

Member Function Documentation

◆ computeLastChild()

template<typename _Scalar , int _Options, template< typename, int > class JointCollectionTpl>
void pinocchio::DataTpl< _Scalar, _Options, JointCollectionTpl >::computeLastChild ( const Model model)
private

◆ computeParents_fromRow()

template<typename _Scalar , int _Options, template< typename, int > class JointCollectionTpl>
void pinocchio::DataTpl< _Scalar, _Options, JointCollectionTpl >::computeParents_fromRow ( const Model model)
private

◆ computeSupports_fromRow()

template<typename _Scalar , int _Options, template< typename, int > class JointCollectionTpl>
void pinocchio::DataTpl< _Scalar, _Options, JointCollectionTpl >::computeSupports_fromRow ( const Model model)
private

◆ PINOCCHIO_ALIGNED_STD_VECTOR() [1/29]

template<typename _Scalar , int _Options, template< typename, int > class JointCollectionTpl>
pinocchio::DataTpl< _Scalar, _Options, JointCollectionTpl >::PINOCCHIO_ALIGNED_STD_VECTOR ( Force  )

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() [2/29]

template<typename _Scalar , int _Options, template< typename, int > class JointCollectionTpl>
pinocchio::DataTpl< _Scalar, _Options, JointCollectionTpl >::PINOCCHIO_ALIGNED_STD_VECTOR ( Force  )

Vector of spatial momenta expressed in the local frame of the joint.

◆ PINOCCHIO_ALIGNED_STD_VECTOR() [3/29]

template<typename _Scalar , int _Options, template< typename, int > class JointCollectionTpl>
pinocchio::DataTpl< _Scalar, _Options, JointCollectionTpl >::PINOCCHIO_ALIGNED_STD_VECTOR ( Force  )

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.

◆ PINOCCHIO_ALIGNED_STD_VECTOR() [4/29]

template<typename _Scalar , int _Options, template< typename, int > class JointCollectionTpl>
pinocchio::DataTpl< _Scalar, _Options, JointCollectionTpl >::PINOCCHIO_ALIGNED_STD_VECTOR ( Force  )

Vector of spatial momenta expressed in the world frame.

◆ PINOCCHIO_ALIGNED_STD_VECTOR() [5/29]

template<typename _Scalar , int _Options, template< typename, int > class JointCollectionTpl>
pinocchio::DataTpl< _Scalar, _Options, JointCollectionTpl >::PINOCCHIO_ALIGNED_STD_VECTOR ( Inertia  )

Rigid Body Inertia supported by the joint expressed in the world frame.

◆ PINOCCHIO_ALIGNED_STD_VECTOR() [6/29]

template<typename _Scalar , int _Options, template< typename, int > class JointCollectionTpl>
pinocchio::DataTpl< _Scalar, _Options, JointCollectionTpl >::PINOCCHIO_ALIGNED_STD_VECTOR ( Inertia  )

Composite Rigid Body Inertia expressed in the world frame.

◆ PINOCCHIO_ALIGNED_STD_VECTOR() [7/29]

template<typename _Scalar , int _Options, template< typename, int > class JointCollectionTpl>
pinocchio::DataTpl< _Scalar, _Options, JointCollectionTpl >::PINOCCHIO_ALIGNED_STD_VECTOR ( Inertia  )

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() [8/29]

template<typename _Scalar , int _Options, template< typename, int > class JointCollectionTpl>
typedef pinocchio::DataTpl< _Scalar, _Options, JointCollectionTpl >::PINOCCHIO_ALIGNED_STD_VECTOR ( JointData  )

◆ PINOCCHIO_ALIGNED_STD_VECTOR() [9/29]

template<typename _Scalar , int _Options, template< typename, int > class JointCollectionTpl>
typedef pinocchio::DataTpl< _Scalar, _Options, JointCollectionTpl >::PINOCCHIO_ALIGNED_STD_VECTOR ( JointModel  )

◆ PINOCCHIO_ALIGNED_STD_VECTOR() [10/29]

template<typename _Scalar , int _Options, template< typename, int > class JointCollectionTpl>
pinocchio::DataTpl< _Scalar, _Options, JointCollectionTpl >::PINOCCHIO_ALIGNED_STD_VECTOR ( Matrix6  )

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() [11/29]

template<typename _Scalar , int _Options, template< typename, int > class JointCollectionTpl>
pinocchio::DataTpl< _Scalar, _Options, JointCollectionTpl >::PINOCCHIO_ALIGNED_STD_VECTOR ( Matrix6  )

Time variation of Composite Rigid Body Inertia expressed in the world frame.

◆ PINOCCHIO_ALIGNED_STD_VECTOR() [12/29]

template<typename _Scalar , int _Options, template< typename, int > class JointCollectionTpl>
pinocchio::DataTpl< _Scalar, _Options, JointCollectionTpl >::PINOCCHIO_ALIGNED_STD_VECTOR ( Matrix6  )

Vector of sub-tree composite rigid body inertia time derivatives $ \dot{Y}_{crb}$. See Data::Ycrb for more details.

◆ PINOCCHIO_ALIGNED_STD_VECTOR() [13/29]

template<typename _Scalar , int _Options, template< typename, int > class JointCollectionTpl>
pinocchio::DataTpl< _Scalar, _Options, JointCollectionTpl >::PINOCCHIO_ALIGNED_STD_VECTOR ( Matrix6  )

Left variation of the inertia matrix.

◆ PINOCCHIO_ALIGNED_STD_VECTOR() [14/29]

template<typename _Scalar , int _Options, template< typename, int > class JointCollectionTpl>
pinocchio::DataTpl< _Scalar, _Options, JointCollectionTpl >::PINOCCHIO_ALIGNED_STD_VECTOR ( Matrix6  )

Right variation of the inertia matrix.

◆ PINOCCHIO_ALIGNED_STD_VECTOR() [15/29]

template<typename _Scalar , int _Options, template< typename, int > class JointCollectionTpl>
pinocchio::DataTpl< _Scalar, _Options, JointCollectionTpl >::PINOCCHIO_ALIGNED_STD_VECTOR ( Matrix6  )

Inertia matrix of the subtree expressed as dense matrix [ABA].

◆ PINOCCHIO_ALIGNED_STD_VECTOR() [16/29]

template<typename _Scalar , int _Options, template< typename, int > class JointCollectionTpl>
pinocchio::DataTpl< _Scalar, _Options, JointCollectionTpl >::PINOCCHIO_ALIGNED_STD_VECTOR ( Matrix6x  )

Spatial forces set, used in CRBA and CCRBA.

◆ PINOCCHIO_ALIGNED_STD_VECTOR() [17/29]

template<typename _Scalar , int _Options, template< typename, int > class JointCollectionTpl>
pinocchio::DataTpl< _Scalar, _Options, JointCollectionTpl >::PINOCCHIO_ALIGNED_STD_VECTOR ( Motion  )

Vector of joint accelerations expressed at the centers of the joints frames.

◆ PINOCCHIO_ALIGNED_STD_VECTOR() [18/29]

template<typename _Scalar , int _Options, template< typename, int > class JointCollectionTpl>
pinocchio::DataTpl< _Scalar, _Options, JointCollectionTpl >::PINOCCHIO_ALIGNED_STD_VECTOR ( Motion  )

Vector of joint accelerations due to the gravity field.

◆ PINOCCHIO_ALIGNED_STD_VECTOR() [19/29]

template<typename _Scalar , int _Options, template< typename, int > class JointCollectionTpl>
pinocchio::DataTpl< _Scalar, _Options, JointCollectionTpl >::PINOCCHIO_ALIGNED_STD_VECTOR ( Motion  )

Vector of joint accelerations expressed at the origin of the world.

◆ PINOCCHIO_ALIGNED_STD_VECTOR() [20/29]

template<typename _Scalar , int _Options, template< typename, int > class JointCollectionTpl>
pinocchio::DataTpl< _Scalar, _Options, JointCollectionTpl >::PINOCCHIO_ALIGNED_STD_VECTOR ( Motion  )

Vector of joint accelerations expressed at the origin of the world including gravity contribution.

◆ PINOCCHIO_ALIGNED_STD_VECTOR() [21/29]

template<typename _Scalar , int _Options, template< typename, int > class JointCollectionTpl>
pinocchio::DataTpl< _Scalar, _Options, JointCollectionTpl >::PINOCCHIO_ALIGNED_STD_VECTOR ( Motion  )

Vector of joint velocities expressed at the origin.

◆ PINOCCHIO_ALIGNED_STD_VECTOR() [22/29]

template<typename _Scalar , int _Options, template< typename, int > class JointCollectionTpl>
pinocchio::DataTpl< _Scalar, _Options, JointCollectionTpl >::PINOCCHIO_ALIGNED_STD_VECTOR ( Motion  )

Vector of joint velocities expressed at the centers of the joints.

◆ PINOCCHIO_ALIGNED_STD_VECTOR() [23/29]

template<typename _Scalar , int _Options, template< typename, int > class JointCollectionTpl>
pinocchio::DataTpl< _Scalar, _Options, JointCollectionTpl >::PINOCCHIO_ALIGNED_STD_VECTOR ( SE3  )

Vector of joint placements wrt to algorithm end effector.

◆ PINOCCHIO_ALIGNED_STD_VECTOR() [24/29]

template<typename _Scalar , int _Options, template< typename, int > class JointCollectionTpl>
pinocchio::DataTpl< _Scalar, _Options, JointCollectionTpl >::PINOCCHIO_ALIGNED_STD_VECTOR ( SE3  )

Vector of relative joint placements (wrt the body parent).

◆ PINOCCHIO_ALIGNED_STD_VECTOR() [25/29]

template<typename _Scalar , int _Options, template< typename, int > class JointCollectionTpl>
pinocchio::DataTpl< _Scalar, _Options, JointCollectionTpl >::PINOCCHIO_ALIGNED_STD_VECTOR ( SE3  )

Vector of absolute operationnel frame placements (wrt the world).

◆ PINOCCHIO_ALIGNED_STD_VECTOR() [26/29]

template<typename _Scalar , int _Options, template< typename, int > class JointCollectionTpl>
pinocchio::DataTpl< _Scalar, _Options, JointCollectionTpl >::PINOCCHIO_ALIGNED_STD_VECTOR ( SE3  )

Vector of absolute joint placements (wrt the world).

◆ PINOCCHIO_ALIGNED_STD_VECTOR() [27/29]

template<typename _Scalar , int _Options, template< typename, int > class JointCollectionTpl>
pinocchio::DataTpl< _Scalar, _Options, JointCollectionTpl >::PINOCCHIO_ALIGNED_STD_VECTOR ( Vector3  )

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() [28/29]

template<typename _Scalar , int _Options, template< typename, int > class JointCollectionTpl>
pinocchio::DataTpl< _Scalar, _Options, JointCollectionTpl >::PINOCCHIO_ALIGNED_STD_VECTOR ( Vector3  )

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() [29/29]

template<typename _Scalar , int _Options, template< typename, int > class JointCollectionTpl>
pinocchio::DataTpl< _Scalar, _Options, JointCollectionTpl >::PINOCCHIO_ALIGNED_STD_VECTOR ( Vector3  )

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.

Member Data Documentation

◆ Ag

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

Centroidal Momentum Matrix.

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

Definition at line 221 of file multibody/data.hpp.

◆ bodyRegressor

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

Body regressor.

Definition at line 372 of file multibody/data.hpp.

◆ C

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

The Coriolis matrix (a square matrix of dim model.nv).

Definition at line 159 of file multibody/data.hpp.

◆ D

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

Diagonal of the joint space intertia matrix obtained by a Cholesky Decomposition.

Definition at line 263 of file multibody/data.hpp.

◆ d2tau_dadq

template<typename _Scalar , int _Options, template< typename, int > class JointCollectionTpl>
Tensor3x pinocchio::DataTpl< _Scalar, _Options, JointCollectionTpl >::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.

Definition at line 396 of file multibody/data.hpp.

◆ d2tau_dqdq

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

SO Partial derivative of the joint torque vector with respect to the joint configuration.

Definition at line 382 of file multibody/data.hpp.

◆ d2tau_dqdv

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

SO Cross-Partial derivative of the joint torque vector with respect to the joint configuration/velocity.

Definition at line 390 of file multibody/data.hpp.

◆ d2tau_dvdv

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

SO Partial derivative of the joint torque vector with respect to the joint velocity.

Definition at line 386 of file multibody/data.hpp.

◆ dAdq

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

Variation of the spatial acceleration set with respect to the joint configuration.

Definition at line 303 of file multibody/data.hpp.

◆ dAdv

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

Variation of the spatial acceleration set with respect to the joint velocity.

Definition at line 306 of file multibody/data.hpp.

◆ dAg

template<typename _Scalar , int _Options, template< typename, int > class JointCollectionTpl>
Matrix6x pinocchio::DataTpl< _Scalar, _Options, JointCollectionTpl >::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 226 of file multibody/data.hpp.

◆ ddJ

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

Second derivative of the Jacobian with respect to the time.

Definition at line 289 of file multibody/data.hpp.

◆ ddq

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

The joint accelerations computed from ABA.

Definition at line 209 of file multibody/data.hpp.

◆ ddq_dq

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

Partial derivative of the joint acceleration vector with respect to the joint configuration.

Definition at line 315 of file multibody/data.hpp.

◆ ddq_dv

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

Partial derivative of the joint acceleration vector with respect to the joint velocity.

Definition at line 318 of file multibody/data.hpp.

◆ dFda

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

Variation of the forceset with respect to the joint acceleration.

Definition at line 171 of file multibody/data.hpp.

◆ dFdq

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

Variation of the forceset with respect to the joint configuration.

Definition at line 165 of file multibody/data.hpp.

◆ dFdv

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

Variation of the forceset with respect to the joint velocity.

Definition at line 168 of file multibody/data.hpp.

◆ dHdq

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

Variation of the spatial momenta with respect to the joint configuration.

Definition at line 162 of file multibody/data.hpp.

◆ dhg

template<typename _Scalar , int _Options, template< typename, int > class JointCollectionTpl>
Force pinocchio::DataTpl< _Scalar, _Options, JointCollectionTpl >::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 238 of file multibody/data.hpp.

◆ Dinv

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

Diagonal inverse of the joint space intertia matrix obtained by a Cholesky Decomposition.

Definition at line 266 of file multibody/data.hpp.

◆ dJ

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

Derivative of the Jacobian with respect to the time.

Definition at line 286 of file multibody/data.hpp.

◆ dq_after

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

Generalized velocity after impact.

Definition at line 363 of file multibody/data.hpp.

◆ dtau_dq

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

Partial derivative of the joint torque vector with respect to the joint configuration.

Definition at line 309 of file multibody/data.hpp.

◆ dtau_dv

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

Partial derivative of the joint torque vector with respect to the joint velocity.

Definition at line 312 of file multibody/data.hpp.

◆ dVdq

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

Variation of the spatial velocity set with respect to the joint configuration.

Definition at line 300 of file multibody/data.hpp.

◆ end_idx_v_fromRow

template<typename _Scalar , int _Options, template< typename, int > class JointCollectionTpl>
std::vector<int> pinocchio::DataTpl< _Scalar, _Options, JointCollectionTpl >::end_idx_v_fromRow

End index of the Joint motion subspace.

Definition at line 257 of file multibody/data.hpp.

◆ g

template<typename _Scalar , int _Options, template< typename, int > class JointCollectionTpl>
VectorXs pinocchio::DataTpl< _Scalar, _Options, JointCollectionTpl >::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 140 of file multibody/data.hpp.

◆ hg

template<typename _Scalar , int _Options, template< typename, int > class JointCollectionTpl>
Force pinocchio::DataTpl< _Scalar, _Options, JointCollectionTpl >::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 232 of file multibody/data.hpp.

◆ Ig

template<typename _Scalar , int _Options, template< typename, int > class JointCollectionTpl>
Inertia pinocchio::DataTpl< _Scalar, _Options, JointCollectionTpl >::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 242 of file multibody/data.hpp.

◆ impulse_c

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

Lagrange Multipliers corresponding to the contact impulses in pinocchio::impulseDynamics.

Definition at line 366 of file multibody/data.hpp.

◆ IS

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

Used in computeMinverse.

Definition at line 180 of file multibody/data.hpp.

◆ Itmp

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

Temporary for derivative algorithms.

Definition at line 201 of file multibody/data.hpp.

◆ J

template<typename _Scalar , int _Options, template< typename, int > class JointCollectionTpl>
Matrix6x pinocchio::DataTpl< _Scalar, _Options, JointCollectionTpl >::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 283 of file multibody/data.hpp.

◆ Jcom

template<typename _Scalar , int _Options, template< typename, int > class JointCollectionTpl>
Matrix3x pinocchio::DataTpl< _Scalar, _Options, JointCollectionTpl >::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 337 of file multibody/data.hpp.

◆ JMinvJt

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

Inverse of the operational-space inertia matrix.

Definition at line 348 of file multibody/data.hpp.

◆ joints

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

Vector of pinocchio::JointData associated to the pinocchio::JointModel stored in model, encapsulated in JointDataAccessor.

Definition at line 89 of file multibody/data.hpp.

◆ jointTorqueRegressor

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

Matrix related to joint torque regressor.

Definition at line 375 of file multibody/data.hpp.

◆ kinematic_hessians

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

Tensor containing the kinematic Hessian of all the joints.

Definition at line 378 of file multibody/data.hpp.

◆ kinetic_energy

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

Kinetic energy of the model.

Definition at line 340 of file multibody/data.hpp.

◆ lambda_c

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

Lagrange Multipliers corresponding to the contact forces in pinocchio::forwardDynamics.

Definition at line 354 of file multibody/data.hpp.

◆ lastChild

template<typename _Scalar , int _Options, template< typename, int > class JointCollectionTpl>
std::vector<int> pinocchio::DataTpl< _Scalar, _Options, JointCollectionTpl >::lastChild

Index of the last child (for CRBA)

Definition at line 248 of file multibody/data.hpp.

◆ llt_JMinvJt

template<typename _Scalar , int _Options, template< typename, int > class JointCollectionTpl>
Eigen::LLT<MatrixXs> pinocchio::DataTpl< _Scalar, _Options, JointCollectionTpl >::llt_JMinvJt

Cholesky decompostion of $JMinvJt$.

Definition at line 351 of file multibody/data.hpp.

◆ M

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

The joint space inertia matrix (a square matrix of dim model.nv).

Definition at line 153 of file multibody/data.hpp.

◆ M6tmp

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

Temporary for derivative algorithms.

Definition at line 204 of file multibody/data.hpp.

◆ M6tmpR

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

Definition at line 205 of file multibody/data.hpp.

◆ M6tmpR2

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

Definition at line 206 of file multibody/data.hpp.

◆ mass

template<typename _Scalar , int _Options, template< typename, int > class JointCollectionTpl>
std::vector<Scalar> pinocchio::DataTpl< _Scalar, _Options, JointCollectionTpl >::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.

Definition at line 333 of file multibody/data.hpp.

◆ Minv

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

The inverse of the joint space inertia matrix (a square matrix of dim model.nv).

Definition at line 156 of file multibody/data.hpp.

◆ nle

template<typename _Scalar , int _Options, template< typename, int > class JointCollectionTpl>
VectorXs pinocchio::DataTpl< _Scalar, _Options, JointCollectionTpl >::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 135 of file multibody/data.hpp.

◆ nvSubtree

template<typename _Scalar , int _Options, template< typename, int > class JointCollectionTpl>
std::vector<int> pinocchio::DataTpl< _Scalar, _Options, JointCollectionTpl >::nvSubtree

Dimension of the subtree motion space (for CRBA)

Definition at line 251 of file multibody/data.hpp.

◆ nvSubtree_fromRow

template<typename _Scalar , int _Options, template< typename, int > class JointCollectionTpl>
std::vector<int> pinocchio::DataTpl< _Scalar, _Options, JointCollectionTpl >::nvSubtree_fromRow

Subtree of the current row index (used in Cholesky Decomposition).

Definition at line 279 of file multibody/data.hpp.

◆ parents_fromRow

template<typename _Scalar , int _Options, template< typename, int > class JointCollectionTpl>
std::vector<int> pinocchio::DataTpl< _Scalar, _Options, JointCollectionTpl >::parents_fromRow

First previous non-zero row in M (used in Cholesky Decomposition).

Definition at line 272 of file multibody/data.hpp.

◆ potential_energy

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

Potential energy of the model.

Definition at line 343 of file multibody/data.hpp.

◆ psid

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

psidot Derivative of Jacobian w.r.t to the parent body moving v(p(j)) x Sj

Definition at line 293 of file multibody/data.hpp.

◆ psidd

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

psiddot Second Derivative of Jacobian w.r.t to the parent body moving a(p(j)) x Sj + v(p(j)) x psidj

Definition at line 297 of file multibody/data.hpp.

◆ Scalar

template<typename _Scalar , int _Options, template< typename, int > class JointCollectionTpl>
EIGEN_MAKE_ALIGNED_OPERATOR_NEW typedef _Scalar pinocchio::DataTpl< _Scalar, _Options, JointCollectionTpl >::Scalar

Definition at line 34 of file multibody/data.hpp.

◆ SDinv

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

Used in computeMinverse.

Definition at line 174 of file multibody/data.hpp.

◆ sDUiJt

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

Temporary corresponding to $ \sqrt{D} U^{-1} J^{\top} $.

Definition at line 357 of file multibody/data.hpp.

◆ start_idx_v_fromRow

template<typename _Scalar , int _Options, template< typename, int > class JointCollectionTpl>
std::vector<int> pinocchio::DataTpl< _Scalar, _Options, JointCollectionTpl >::start_idx_v_fromRow

Starting index of the Joint motion subspace.

Definition at line 254 of file multibody/data.hpp.

◆ staticRegressor

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

Matrix related to static regressor.

Definition at line 369 of file multibody/data.hpp.

◆ supports_fromRow

template<typename _Scalar , int _Options, template< typename, int > class JointCollectionTpl>
std::vector< std::vector<int> > pinocchio::DataTpl< _Scalar, _Options, JointCollectionTpl >::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.

Definition at line 276 of file multibody/data.hpp.

◆ tau

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

Vector of joint torques (dim model.nv).

Definition at line 130 of file multibody/data.hpp.

◆ tmp

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

Temporary of size NV used in Cholesky Decomposition.

Definition at line 269 of file multibody/data.hpp.

◆ torque_residual

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

Temporary corresponding to the residual torque $ \tau - b(q,\dot{q}) $.

Definition at line 360 of file multibody/data.hpp.

◆ u

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

Intermediate quantity corresponding to apparent torque [ABA].

Definition at line 216 of file multibody/data.hpp.

◆ U

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

Joint space intertia matrix square root (upper trianglular part) computed with a Cholesky Decomposition.

Definition at line 260 of file multibody/data.hpp.

◆ UDinv

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

Used in computeMinverse.

Definition at line 177 of file multibody/data.hpp.


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


pinocchio
Author(s):
autogenerated on Tue Feb 13 2024 03:44:01