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

#include <generic.hpp>

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 Eigen::Matrix< Scalar, 1, Eigen::Dynamic, Options|Eigen::RowMajor > RowVectorXs
 
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, OptionsVector6
 
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 at the origin of the world. For each body, the force represents the sum of all external forces acting on the body. More...
 
 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. More...
 
 PINOCCHIO_ALIGNED_STD_VECTOR (Force) oh
 Vector of spatial momenta expressed at the origin of the world. 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...
 
 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. 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) extended_motion_propagator2
 
 PINOCCHIO_ALIGNED_STD_VECTOR (Matrix6) Ivx
 Left variation of the inertia matrix. More...
 
 PINOCCHIO_ALIGNED_STD_VECTOR (Matrix6) oK
 Inverse articulated inertia. More...
 
 PINOCCHIO_ALIGNED_STD_VECTOR (Matrix6) oL
 Acceleration propagator. More...
 
 PINOCCHIO_ALIGNED_STD_VECTOR (Matrix6) oYaba
 Articulated Body Inertia matrix of the subtree expressed in the WORLD coordinate frame. More...
 
 PINOCCHIO_ALIGNED_STD_VECTOR (Matrix6) spatial_inv_inertia
 
 PINOCCHIO_ALIGNED_STD_VECTOR (Matrix6) vxI
 Right variation of the inertia matrix. More...
 
 PINOCCHIO_ALIGNED_STD_VECTOR (Matrix6) Yaba
 Articulated Body Inertia matrix of the subtree expressed in the LOCAL coordinate frame of the joint. More...
 
 PINOCCHIO_ALIGNED_STD_VECTOR (Matrix6x) Fcrb
 Spatial forces set, used in CRBA and CCRBA. More...
 
 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. More...
 
 PINOCCHIO_ALIGNED_STD_VECTOR (Motion) a_bias
 
 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_augmented
 Vector of joint accelerations expressed at the origin of the world. These accelerations are used in the context of augmented Lagrangian algorithms. More...
 
 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. More...
 
 PINOCCHIO_ALIGNED_STD_VECTOR (Motion) oa_gf
 Vector of joint accelerations expressed at the origin of the world including the gravity contribution. More...
 
 PINOCCHIO_ALIGNED_STD_VECTOR (Motion) ov
 Vector of joint velocities expressed at the origin of the world. More...
 
 PINOCCHIO_ALIGNED_STD_VECTOR (Motion) v
 Vector of joint velocities expressed in the local frame of the joint. 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 (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. 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...
 
 PINOCCHIO_ALIGNED_STD_VECTOR (VectorXs) lA
 
 PINOCCHIO_ALIGNED_STD_VECTOR (VectorXs) lambdaA
 

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...
 
ContactCholeskyDecomposition contact_chol
 Cholesky decomposition of the KKT contact matrix. More...
 
PINOCCHIO_COMPILER_DIAGNOSTIC_PUSH PINOCCHIO_COMPILER_DIAGNOSTIC_IGNORED_DEPRECECATED_DECLARATIONS typedef ContactCholeskyDecompositionTpl< Scalar, OptionsContactCholeskyDecomposition
 
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...
 
MatrixXs dac_da
 
MatrixXs dac_dq
 
MatrixXs dac_dv
 
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...
 
RowMatrixXs ddq_dq
 Partial derivative of the joint acceleration vector with respect to the joint configuration. More...
 
RowMatrixXs ddq_dtau
 Partial derivative of the joint acceleration vector with respect to the joint torques. More...
 
RowMatrixXs 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 set with respect to the joint configuration. More...
 
Force dhg
 Centroidal momentum time derivative. More...
 
VectorXs diff_lambda_c
 Difference between two consecutive iterations of the proxy algorithm. 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...
 
MatrixXs dlambda_dq
 Partial derivatives of the constraints forces with respect to the joint configuration, velocity and torque;. More...
 
MatrixXs dlambda_dtau
 
MatrixXs dlambda_dv
 
MatrixXs dlambda_dx_prox
 
TangentVectorType dq_after
 Generalized velocity after impact. More...
 
MatrixXs drhs_prox
 
RowMatrixXs dtau_dq
 Partial derivative of the joint torque vector with respect to the joint configuration. More...
 
RowMatrixXs dtau_dv
 Partial derivative of the joint torque vector with respect to the joint velocity. More...
 
MatrixXs dvc_dq
 Stack of partial derivative of the contact frame acceleration with respect to the joint parameters. 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...
 
 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. 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...
 
PINOCCHIO_COMPILER_DIAGNOSTIC_POP 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 system. More...
 
RowVectorXs kineticEnergyRegressor
 Matrix related to kinetic energy regressor. More...
 
VectorXs lambda_c
 Lagrange Multipliers corresponding to the contact forces in pinocchio::forwardDynamics. More...
 
VectorXs lambda_c_prox
 Proximal Lagrange Multipliers used in the computation of the Forward Dynamics computations. 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...
 
Scalar mechanical_energy
 Mechanical energy of the system. 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...
 
MatrixXs osim
 Operational space inertia matrix;. More...
 
Eigen::LLT< MatrixXsosim_llt
 
 oYaba_contact
 Articulated Body Inertia matrix with contact apparent inertia, of a given the subtree and expressed in the WORLD coordinate frame. 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 system. More...
 
RowVectorXs potentialEnergyRegressor
 Matrix related to potential energy regressor. More...
 
VectorXs primal_dual_contact_solution
 RHS vector when solving the contact dynamics KKT problem. More...
 
VectorXs primal_rhs_contact
 Primal RHS in contact dynamic equations. 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 25 of file context/generic.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 102 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 84 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 58 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 60 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 65 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 64 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 62 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 66 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 59 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 52 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 69 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 63 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 68 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 94 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 96 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 92 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 74 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 54 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 57 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 97 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 99 of file multibody/data.hpp.

◆ RowVectorXs

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

Definition at line 76 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 56 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 89 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 105 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 77 of file multibody/data.hpp.

◆ Vector6

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

Definition at line 78 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 80 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 81 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 75 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 47 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>
template PINOCCHIO_EXPLICIT_INSTANTIATION_DEFINITION_DLLAPI pinocchio::DataTpl< _Scalar, _Options, JointCollectionTpl >::DataTpl ( )
inline

Default constructor.

Definition at line 590 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/52]

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/52]

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/52]

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

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. These forces are used in the context of augmented Lagrangian algorithms.

◆ PINOCCHIO_ALIGNED_STD_VECTOR() [5/52]

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 at the origin of the world.

◆ PINOCCHIO_ALIGNED_STD_VECTOR() [6/52]

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

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

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

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

◆ PINOCCHIO_ALIGNED_STD_VECTOR() [10/52]

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

◆ PINOCCHIO_ALIGNED_STD_VECTOR() [11/52]

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

◆ PINOCCHIO_ALIGNED_STD_VECTOR() [12/52]

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

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

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

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

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

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

◆ PINOCCHIO_ALIGNED_STD_VECTOR() [18/52]

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

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

Inverse articulated inertia.

◆ PINOCCHIO_ALIGNED_STD_VECTOR() [20/52]

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

Acceleration propagator.

◆ PINOCCHIO_ALIGNED_STD_VECTOR() [21/52]

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

Articulated Body Inertia matrix of the subtree expressed in the WORLD coordinate frame.

◆ PINOCCHIO_ALIGNED_STD_VECTOR() [22/52]

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

◆ PINOCCHIO_ALIGNED_STD_VECTOR() [23/52]

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

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

Articulated Body Inertia matrix of the subtree expressed in the LOCAL coordinate frame of the joint.

◆ PINOCCHIO_ALIGNED_STD_VECTOR() [25/52]

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

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

◆ PINOCCHIO_ALIGNED_STD_VECTOR() [27/52]

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

◆ PINOCCHIO_ALIGNED_STD_VECTOR() [28/52]

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

◆ PINOCCHIO_ALIGNED_STD_VECTOR() [29/52]

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 in the local frame of the joint.

◆ PINOCCHIO_ALIGNED_STD_VECTOR() [30/52]

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

◆ PINOCCHIO_ALIGNED_STD_VECTOR() [31/52]

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

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

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. These accelerations are used in the context of augmented Lagrangian algorithms.

◆ PINOCCHIO_ALIGNED_STD_VECTOR() [34/52]

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. These accelerations are used in the context of augmented Lagrangian algorithms.

◆ PINOCCHIO_ALIGNED_STD_VECTOR() [35/52]

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 the gravity contribution.

◆ PINOCCHIO_ALIGNED_STD_VECTOR() [36/52]

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 of the world.

◆ PINOCCHIO_ALIGNED_STD_VECTOR() [37/52]

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 in the local frame of the joint.

◆ PINOCCHIO_ALIGNED_STD_VECTOR() [38/52]

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

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

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

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

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

◆ PINOCCHIO_ALIGNED_STD_VECTOR() [43/52]

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

◆ PINOCCHIO_ALIGNED_STD_VECTOR() [44/52]

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

◆ PINOCCHIO_ALIGNED_STD_VECTOR() [45/52]

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

◆ PINOCCHIO_ALIGNED_STD_VECTOR() [46/52]

template<typename _Scalar , int _Options, template< typename, int > class JointCollectionTpl>
pinocchio::DataTpl< _Scalar, _Options, JointCollectionTpl >::PINOCCHIO_ALIGNED_STD_VECTOR ( std::set< size_t >  ) const

◆ PINOCCHIO_ALIGNED_STD_VECTOR() [47/52]

template<typename _Scalar , int _Options, template< typename, int > class JointCollectionTpl>
pinocchio::DataTpl< _Scalar, _Options, JointCollectionTpl >::PINOCCHIO_ALIGNED_STD_VECTOR ( std::vector< size_t >  ) const

◆ PINOCCHIO_ALIGNED_STD_VECTOR() [48/52]

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

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

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.

◆ PINOCCHIO_ALIGNED_STD_VECTOR() [51/52]

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

◆ PINOCCHIO_ALIGNED_STD_VECTOR() [52/52]

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

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 284 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 497 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 205 of file multibody/data.hpp.

◆ contact_chol

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

Cholesky decomposition of the KKT contact matrix.

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

◆ ContactCholeskyDecomposition

template<typename _Scalar , int _Options, template< typename, int > class JointCollectionTpl>
PINOCCHIO_COMPILER_DIAGNOSTIC_PUSH PINOCCHIO_COMPILER_DIAGNOSTIC_IGNORED_DEPRECECATED_DECLARATIONS typedef ContactCholeskyDecompositionTpl<Scalar, Options> pinocchio::DataTpl< _Scalar, _Options, JointCollectionTpl >::ContactCholeskyDecomposition

Definition at line 110 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 332 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 562 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 548 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 556 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 552 of file multibody/data.hpp.

◆ dac_da

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

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

◆ dac_dq

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

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

◆ dac_dv

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

Definition at line 408 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 380 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 383 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 290 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 366 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 256 of file multibody/data.hpp.

◆ ddq_dq

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

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

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

◆ ddq_dtau

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

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

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

◆ ddq_dv

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

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

Definition at line 398 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 217 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 211 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 214 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 set with respect to the joint configuration.

Definition at line 208 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 305 of file multibody/data.hpp.

◆ diff_lambda_c

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

Difference between two consecutive iterations of the proxy algorithm.

Definition at line 478 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 336 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 363 of file multibody/data.hpp.

◆ dlambda_dq

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

Partial derivatives of the constraints forces with respect to the joint configuration, velocity and torque;.

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

◆ dlambda_dtau

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

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

◆ dlambda_dv

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

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

◆ dlambda_dx_prox

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

Definition at line 419 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 487 of file multibody/data.hpp.

◆ drhs_prox

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

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

◆ dtau_dq

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

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

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

◆ dtau_dv

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

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

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

◆ dvc_dq

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

Stack of partial derivative of the contact frame acceleration with respect to the joint parameters.

Definition at line 406 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 377 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 325 of file multibody/data.hpp.

◆ extended_motion_propagator

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

Definition at line 569 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 184 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 297 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 310 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 491 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 226 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 248 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 360 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 450 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 464 of file multibody/data.hpp.

◆ joints

template<typename _Scalar , int _Options, template< typename, int > class JointCollectionTpl>
PINOCCHIO_COMPILER_DIAGNOSTIC_POP 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 115 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 500 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 525 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 system.

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

◆ kineticEnergyRegressor

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

Matrix related to kinetic energy regressor.

Definition at line 503 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 471 of file multibody/data.hpp.

◆ lambda_c_prox

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

Proximal Lagrange Multipliers used in the computation of the Forward Dynamics computations.

Definition at line 475 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 316 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 467 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 199 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 251 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 252 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 253 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 444 of file multibody/data.hpp.

◆ mechanical_energy

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

Mechanical energy of the system.

Definition at line 459 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 202 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 179 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 319 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 351 of file multibody/data.hpp.

◆ osim

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

Operational space inertia matrix;.

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

◆ osim_llt

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

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

◆ oYaba_contact

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

Articulated Body Inertia matrix with contact apparent inertia, of a given the subtree and expressed in the WORLD coordinate frame.

Definition at line 270 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 342 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 system.

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

◆ potentialEnergyRegressor

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

Matrix related to potential energy regressor.

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

◆ primal_dual_contact_solution

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

RHS vector when solving the contact dynamics KKT problem.

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

◆ primal_rhs_contact

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

Primal RHS in contact dynamic equations.

Definition at line 538 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 370 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 374 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 46 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 220 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 481 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 322 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 494 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 348 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 173 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 339 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 484 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 279 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 329 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 223 of file multibody/data.hpp.


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


pinocchio
Author(s):
autogenerated on Wed Jun 19 2024 02:41:19