Template Struct DataTpl
Defined in File data.hpp
Inheritance Relationships
Base Type
public pinocchio::serialization::Serializable< DataTpl< _Scalar, _Options, JointCollectionTpl > >
(Template Struct Serializable)
Struct Documentation
-
template<typename _Scalar, int _Options, template<typename, int> class JointCollectionTpl>
struct DataTpl : public pinocchio::serialization::Serializable<DataTpl<_Scalar, _Options, JointCollectionTpl>> Public Types
Values:
-
enumerator Options
-
enumerator Options
-
typedef JointCollectionTpl<Scalar, Options> JointCollection
-
typedef ModelTpl<Scalar, Options, JointCollectionTpl> Model
-
typedef InertiaTpl<Scalar, Options> Inertia
-
typedef pinocchio::Index Index
-
typedef pinocchio::JointIndex JointIndex
-
typedef pinocchio::GeomIndex GeomIndex
-
typedef pinocchio::FrameIndex FrameIndex
-
typedef JointModelTpl<Scalar, Options, JointCollectionTpl> JointModel
-
typedef JointDataTpl<Scalar, Options, JointCollectionTpl> JointData
-
typedef Eigen::Matrix<Scalar, Eigen::Dynamic, Eigen::Dynamic, Options> MatrixXs
-
typedef Eigen::Matrix<Scalar, Eigen::Dynamic, 1, Options> VectorXs
-
typedef Eigen::Matrix<Scalar, 3, 1, Options> Vector3
-
typedef Eigen::Matrix<Scalar, 6, 1, Options> Vector6c
-
typedef Eigen::Matrix<Scalar, 1, 6, Eigen::RowMajor | Options> Vector6r
-
typedef VectorXs TangentVectorType
Dense vectorized version of a joint tangent vector (e.g. velocity, acceleration, etc). It also handles the notion of co-tangent vector (e.g. torque, etc).
-
typedef Eigen::Matrix<Scalar, 6, Eigen::Dynamic, Options> Matrix6x
The 6d jacobian type (temporary)
-
typedef Eigen::Matrix<Scalar, 3, Eigen::Dynamic, Options> Matrix3x
The 3d jacobian type (temporary)
-
typedef Eigen::Matrix<Scalar, 6, 6, Options> Matrix6
-
typedef Eigen::Matrix<Scalar, 6, 6, Eigen::RowMajor | Options> RowMatrix6
-
typedef Eigen::Matrix<Scalar, Eigen::Dynamic, Eigen::Dynamic, Eigen::RowMajor | Options> RowMatrixXs
-
typedef Eigen::Matrix<Scalar, 6, 10, Options> BodyRegressorType
The type of the body regressor.
Public Functions
- typedef PINOCCHIO_ALIGNED_STD_VECTOR (JointModel) JointModelVector
- typedef PINOCCHIO_ALIGNED_STD_VECTOR (JointData) JointDataVector
- PINOCCHIO_ALIGNED_STD_VECTOR (Motion) a
Vector of joint accelerations expressed at the centers of the joints frames.
- PINOCCHIO_ALIGNED_STD_VECTOR (Motion) oa
Vector of joint accelerations expressed at the origin of the world.
- PINOCCHIO_ALIGNED_STD_VECTOR (Motion) a_gf
Vector of joint accelerations due to the gravity field.
- PINOCCHIO_ALIGNED_STD_VECTOR (Motion) oa_gf
Vector of joint accelerations expressed at the origin of the world including gravity contribution.
- PINOCCHIO_ALIGNED_STD_VECTOR (Motion) v
Vector of joint velocities expressed at the centers of the joints.
- PINOCCHIO_ALIGNED_STD_VECTOR (Motion) ov
Vector of joint velocities expressed at the origin.
- PINOCCHIO_ALIGNED_STD_VECTOR (Force) f
Vector of body forces expressed in the local frame of the joint. For each body, the force represents the sum of all external forces acting on the body.
- PINOCCHIO_ALIGNED_STD_VECTOR (Force) 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.
- PINOCCHIO_ALIGNED_STD_VECTOR (Force) h
Vector of spatial momenta expressed in the local frame of the joint.
- PINOCCHIO_ALIGNED_STD_VECTOR (Force) oh
Vector of spatial momenta expressed in the world frame.
- PINOCCHIO_ALIGNED_STD_VECTOR (SE3) oMi
Vector of absolute joint placements (wrt the world).
- PINOCCHIO_ALIGNED_STD_VECTOR (SE3) liMi
Vector of relative joint placements (wrt the body parent).
- PINOCCHIO_ALIGNED_STD_VECTOR (SE3) oMf
Vector of absolute operationnel frame placements (wrt the world).
- PINOCCHIO_ALIGNED_STD_VECTOR (Inertia) Ycrb
Vector of sub-tree composite rigid body inertias, i.e. the apparent inertia of the subtree supported by the joint and expressed in the local frame of the joint..
- PINOCCHIO_ALIGNED_STD_VECTOR (Matrix6) dYcrb
Vector of sub-tree composite rigid body inertia time derivatives \( \dot{Y}_{crb}\). See Data::Ycrb for more details.
- PINOCCHIO_ALIGNED_STD_VECTOR (Matrix6) vxI
Right variation of the inertia matrix.
- PINOCCHIO_ALIGNED_STD_VECTOR (Matrix6) Ivx
Left variation of the inertia matrix.
- PINOCCHIO_ALIGNED_STD_VECTOR (Matrix6) B
Combined variations of the inertia matrix \( B_i = \frac{1}{2} [(v_i\times∗)I_i + (I_i v_i)\times^{∗} − I_i(v_i\times)] \) consistent with Christoffel symbols.
- PINOCCHIO_ALIGNED_STD_VECTOR (Inertia) oinertias
Rigid Body Inertia supported by the joint expressed in the world frame.
- PINOCCHIO_ALIGNED_STD_VECTOR (Inertia) oYcrb
Composite Rigid Body Inertia expressed in the world frame.
- PINOCCHIO_ALIGNED_STD_VECTOR (Matrix6) doYcrb
Time variation of Composite Rigid Body Inertia expressed in the world frame.
- PINOCCHIO_ALIGNED_STD_VECTOR (Matrix6) Yaba
Inertia matrix of the subtree expressed as dense matrix [ABA].
- PINOCCHIO_ALIGNED_STD_VECTOR (Matrix6x) Fcrb
Spatial forces set, used in CRBA and CCRBA.
- PINOCCHIO_ALIGNED_STD_VECTOR (SE3) iMf
Vector of joint placements wrt to algorithm end effector.
- PINOCCHIO_ALIGNED_STD_VECTOR (Vector3) com
Vector of subtree center of mass positions expressed in the root joint of the subtree. In other words, com[j] is the CoM position of the subtree supported by joint \( j \) and expressed in the joint frame \( j \). The element com[0] corresponds to the center of mass position of the whole model and expressed in the global frame.
- PINOCCHIO_ALIGNED_STD_VECTOR (Vector3) vcom
Vector of subtree center of mass linear velocities expressed in the root joint of the subtree. In other words, vcom[j] is the CoM linear velocity of the subtree supported by joint \( j \) and expressed in the joint frame \( j \). The element vcom[0] corresponds to the velocity of the CoM of the whole model expressed in the global frame.
- PINOCCHIO_ALIGNED_STD_VECTOR (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.
-
explicit DataTpl(const Model &model)
Default constructor of pinocchio::Data from a pinocchio::Model.
- Parameters:
model – [in] The model structure of the rigid body system.
-
inline DataTpl()
Default constructor.
Public Members
- EIGEN_MAKE_ALIGNED_OPERATOR_NEW typedef _Scalar Scalar
-
JointDataVector joints
Vector of pinocchio::JointData associated to the pinocchio::JointModel stored in model, encapsulated in JointDataAccessor.
-
TangentVectorType tau
Vector of joint torques (dim model.nv).
-
VectorXs nle
Vector of Non Linear Effects (dim model.nv). It corresponds to concatenation of the Coriolis, centrifugal and gravitational effects.
Note
In the multibody dynamics equation \( M\ddot{q} + b(q, \dot{q}) = \tau \), the non linear effects are associated to the term \(b\).
-
VectorXs g
Vector of generalized gravity (dim model.nv).
Note
In the multibody dynamics equation \( M\ddot{q} + c(q, \dot{q}) + g(q) = \tau \), the gravity effect is associated to the \(g\) term.
-
RowMatrixXs Minv
The inverse of the joint space inertia matrix (a square matrix of dim model.nv).
-
RowMatrix6 M6tmpR
-
RowMatrix6 M6tmpR2
-
TangentVectorType ddq
The joint accelerations computed from ABA.
-
TangentVectorType u
Intermediate quantity corresponding to apparent torque [ABA].
-
Matrix6x Ag
Centroidal Momentum Matrix.
Note
\( hg = A_g \dot{q}\) maps the joint velocity set to the centroidal momentum.
-
Matrix6x dAg
Centroidal Momentum Matrix Time Variation.
Note
\( \dot{h_g} = A_g \ddot{q}\ + \dot{A_g}\dot{q}\) maps the joint velocity and acceleration vectors to the time variation of the centroidal momentum.
-
Force hg
Centroidal momentum quantity.
Note
The centroidal momentum is expressed in the frame centered at the CoM and aligned with the inertial frame (i.e. the world frame).
Note
\( h_g = \left( m\dot{c}, L_{g} \right); \). \( h_g \) is the stack of the linear momentum and the angular momemtum vectors.
-
Force dhg
Centroidal momentum time derivative.
Note
The centroidal momentum time derivative is expressed in the frame centered at the CoM and aligned with the inertial frame (i.e. the world frame).
Note
\( \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.
-
Inertia Ig
Centroidal Composite Rigid Body Inertia.
Note
\( hg = Ig v_{\text{mean}}\) map a mean velocity to the current centroidal momentum quantity.
-
std::vector<int> lastChild
Index of the last child (for CRBA)
-
std::vector<int> nvSubtree
Dimension of the subtree motion space (for CRBA)
-
std::vector<int> start_idx_v_fromRow
Starting index of the Joint motion subspace.
-
std::vector<int> end_idx_v_fromRow
End index of the Joint motion subspace.
-
MatrixXs U
Joint space intertia matrix square root (upper trianglular part) computed with a Cholesky Decomposition.
-
VectorXs Dinv
Diagonal inverse of the joint space intertia matrix obtained by a Cholesky Decomposition.
-
std::vector<int> parents_fromRow
First previous non-zero row in M (used in Cholesky Decomposition).
-
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.
-
std::vector<int> nvSubtree_fromRow
Subtree of the current row index (used in Cholesky Decomposition).
-
Matrix6x 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
-
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
-
MatrixXs dtau_dq
Partial derivative of the joint torque vector with respect to the joint configuration.
-
MatrixXs ddq_dq
Partial derivative of the joint acceleration vector with respect to the joint configuration.
-
MatrixXs ddq_dv
Partial derivative of the joint acceleration vector with respect to the joint velocity.
-
std::vector<Scalar> mass
Vector of subtree mass. In other words, mass[j] is the mass of the subtree supported by joint \( j \). The element mass[0] corresponds to the total mass of the model.
-
Matrix3x Jcom
Jacobian of center of mass.
Note
This Jacobian maps the joint velocity vector to the velocity of the center of mass, expressed in the inertial frame. In other words, \( v_{\text{CoM}} = J_{\text{CoM}} \dot{q}\).
-
Scalar kinetic_energy
Kinetic energy of the model.
-
Scalar potential_energy
Potential energy of the model.
-
VectorXs lambda_c
Lagrange Multipliers corresponding to the contact forces in pinocchio::forwardDynamics.
-
TangentVectorType dq_after
Generalized velocity after impact.
-
VectorXs impulse_c
Lagrange Multipliers corresponding to the contact impulses in pinocchio::impulseDynamics.
-
BodyRegressorType bodyRegressor
Body regressor.
-
Tensor3x d2tau_dqdq
SO Partial derivative of the joint torque vector with respect to the joint configuration.
-
Tensor3x d2tau_dvdv
SO Partial derivative of the joint torque vector with respect to the joint velocity.