Go to the documentation of this file.
6 #ifndef __pinocchio_multibody_data_hpp__
7 #define __pinocchio_multibody_data_hpp__
23 #include <Eigen/Cholesky>
24 #include <Eigen/StdVector>
25 #include <Eigen/src/Core/util/Constants.h>
33 template<
typename _Scalar,
int _Options,
template<
typename,
int>
class JointCollectionTpl>
39 template<
typename _Scalar,
int _Options,
template<
typename,
int>
class JointCollectionTpl>
42 ,
NumericalBase<DataTpl<_Scalar, _Options, JointCollectionTpl>>
44 EIGEN_MAKE_ALIGNED_OPERATOR_NEW
74 typedef Eigen::Matrix<Scalar, Eigen::Dynamic, Eigen::Dynamic, Options>
MatrixXs;
75 typedef Eigen::Matrix<Scalar, Eigen::Dynamic, 1, Options>
VectorXs;
76 typedef Eigen::Matrix<Scalar, 1, Eigen::Dynamic, Options | Eigen::RowMajor>
RowVectorXs;
77 typedef Eigen::Matrix<Scalar, 3, 1, Options>
Vector3;
78 typedef Eigen::Matrix<Scalar, 6, 1, Options>
Vector6;
80 typedef Eigen::Matrix<Scalar, 6, 1, Options>
Vector6c;
81 typedef Eigen::Matrix<Scalar, 1, 6, Eigen::RowMajor | Options>
Vector6r;
92 typedef Eigen::Matrix<Scalar, 6, Eigen::Dynamic, Options>
Matrix6x;
94 typedef Eigen::Matrix<Scalar, 3, Eigen::Dynamic, Options>
Matrix3x;
96 typedef Eigen::Matrix<Scalar, 6, 6, Options>
Matrix6;
97 typedef Eigen::Matrix<Scalar, 6, 6, Eigen::RowMajor | Options>
RowMatrix6;
98 typedef Eigen::Matrix<Scalar, Eigen::Dynamic, Eigen::Dynamic, Eigen::RowMajor | Options>
518 #if defined(_MSC_VER)
521 #pragma warning(disable : 4554)
527 #if defined(_MSC_VER)
528 #pragma warning(default : 4554) // C4554 enabled after tensor definition
540 #if defined(_MSC_VER)
543 #pragma warning(disable : 4554)
564 #if defined(_MSC_VER)
565 #pragma warning(default : 4554) // C4554 enabled after tensor definition
605 #include "pinocchio/multibody/data.hxx"
607 #if PINOCCHIO_ENABLE_TEMPLATE_INSTANTIATION
608 #include "pinocchio/multibody/data.txx"
609 #endif // PINOCCHIO_ENABLE_TEMPLATE_INSTANTIATION
611 #endif // ifndef __pinocchio_multibody_data_hpp__
Tensor3x d2tau_dvdv
SO Partial derivative of the joint torque vector with respect to the joint velocity.
JointModelTpl< Scalar, Options, JointCollectionTpl > JointModel
VectorXs TangentVectorType
Dense vectorized version of a joint tangent vector (e.g. velocity, acceleration, etc)....
MatrixXs M
The joint space inertia matrix (a square matrix of dim model.nv).
std::vector< int > parents_fromRow
First previous non-zero row in M (used in Cholesky Decomposition).
Eigen::Matrix< Scalar, Eigen::Dynamic, Eigen::Dynamic, Options > MatrixXs
RowMatrixXs ddq_dv
Partial derivative of the joint acceleration vector with respect to the joint velocity.
EIGEN_MAKE_ALIGNED_OPERATOR_NEW typedef _Scalar Scalar
TangentVectorType ddq
The joint accelerations computed from ABA.
MatrixXs JMinvJt
Inverse of the operational-space inertia matrix.
Matrix6x dFdq
Variation of the forceset with respect to the joint configuration.
void computeLastChild(const Model &model)
Tensor3x d2tau_dqdq
SO Partial derivative of the joint torque vector with respect to the joint configuration.
pinocchio::GeomIndex GeomIndex
VectorXs g
Vector of generalized gravity (dim model.nv).
RowVectorXs kineticEnergyRegressor
Matrix related to kinetic energy regressor.
Eigen::LLT< MatrixXs > osim_llt
typedef PINOCCHIO_ALIGNED_STD_VECTOR(JointModel) JointModelVector
Matrix6x UDinv
Used in computeMinverse.
Matrix6 M6tmp
Temporary for derivative algorithms.
Matrix6x dAdv
Variation of the spatial acceleration set with respect to the joint velocity.
Matrix6x dAg
Centroidal Momentum Matrix Time Variation.
std::vector< Scalar > mass
Vector of subtree mass. In other words, mass[j] is the mass of the subtree supported by joint ....
MatrixXs dvc_dq
Stack of partial derivative of the contact frame acceleration with respect to the joint parameters.
Force dhg
Centroidal momentum time derivative.
pinocchio::JointIndex JointIndex
Eigen::Matrix< Scalar, Eigen::Dynamic, Eigen::Dynamic, Eigen::RowMajor|Options > RowMatrixXs
Matrix6x dJ
Derivative of the Jacobian with respect to the time.
VectorXs lambda_c_prox
Proximal Lagrange Multipliers used in the computation of the Forward Dynamics computations.
VectorXs ConfigVectorType
Dense vectorized version of a joint configuration vector.
Tensor3x d2tau_dqdv
SO Cross-Partial derivative of the joint torque vector with respect to the joint configuration/veloci...
Scalar kinetic_energy
Kinetic energy of the system.
PINOCCHIO_COMPILER_DIAGNOSTIC_PUSH PINOCCHIO_COMPILER_DIAGNOSTIC_IGNORED_DEPRECECATED_DECLARATIONS typedef ContactCholeskyDecompositionTpl< Scalar, Options > ContactCholeskyDecomposition
MatrixXs jointTorqueRegressor
Matrix related to joint torque regressor.
Eigen::Matrix< Scalar, 6, 6, Eigen::RowMajor|Options > RowMatrix6
Matrix6x dFdv
Variation of the forceset with respect to the joint velocity.
Tensor3x kinematic_hessians
Tensor containing the kinematic Hessian of all the joints.
pinocchio::FrameIndex FrameIndex
#define PINOCCHIO_COMPILER_DIAGNOSTIC_POP
VectorXs lambda_c
Lagrange Multipliers corresponding to the contact forces in pinocchio::forwardDynamics.
TangentVectorType u
Intermediate quantity corresponding to apparent torque [ABA].
std::vector< int > nvSubtree
Dimension of the subtree motion space (for CRBA)
Matrix6x dFda
Variation of the forceset with respect to the joint acceleration.
Matrix6x ddJ
Second derivative of the Jacobian with respect to the time.
PINOCCHIO_COMPILER_DIAGNOSTIC_POP JointDataVector joints
Vector of pinocchio::JointData associated to the pinocchio::JointModel stored in model,...
Matrix6x SDinv
Used in computeMinverse.
std::vector< int > end_idx_v_fromRow
End index of the Joint motion subspace.
Matrix6 Itmp
Temporary for derivative algorithms.
MatrixXs sDUiJt
Temporary corresponding to .
Eigen::Matrix< Scalar, 6, 1, Options > Vector6c
Eigen::Matrix< Scalar, 6, 1, Options > Vector6
A Plucker coordinate frame attached to a parent joint inside a kinematic tree.
Scalar potential_energy
Potential energy of the system.
PINOCCHIO_COMPILER_DIAGNOSTIC_POP typedef std::size_t Index
extended_motion_propagator
RowMatrixXs ddq_dtau
Partial derivative of the joint acceleration vector with respect to the joint torques.
Matrix3x staticRegressor
Matrix related to static regressor.
MatrixXs C
The Coriolis matrix (a square matrix of dim model.nv).
InertiaTpl< Scalar, Options > Inertia
Eigen::Matrix< Scalar, Eigen::Dynamic, 1, Options > VectorXs
Tensor< Scalar, 3, Options > Tensor3x
 
JointDataTpl< Scalar, Options, JointCollectionTpl > JointData
oYaba_contact
Articulated Body Inertia matrix with contact apparent inertia, of a given the subtree and expressed i...
Eigen::Matrix< Scalar, 3, Eigen::Dynamic, Options > Matrix3x
The 3d jacobian type (temporary)
RowMatrixXs dtau_dq
Partial derivative of the joint torque vector with respect to the joint configuration.
void computeSupports_fromRow(const Model &model)
Tensor3x d2tau_dadq
SO Cross-Partial derivative of the joint torque vector with respect to the joint acceleration/configu...
Eigen::Matrix< Scalar, 3, 1, Options > Vector3
std::vector< int > nvSubtree_fromRow
Subtree of the current row index (used in Cholesky Decomposition).
TangentVectorType tau
Vector of joint torques (dim model.nv).
RowMatrixXs Minv
The inverse of the joint space inertia matrix (a square matrix of dim model.nv).
MatrixXs dlambda_dq
Partial derivatives of the constraints forces with respect to the joint configuration,...
VectorXs diff_lambda_c
Difference between two consecutive iterations of the proxy algorithm.
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
Matrix3x Jcom
Jacobian of center of mass.
#define PINOCCHIO_COMPILER_DIAGNOSTIC_IGNORED_DEPRECECATED_DECLARATIONS
void set(bool ownStorage, Vec3f *points_, unsigned int num_points_)
VectorXs primal_rhs_contact
Primal RHS in contact dynamic equations.
#define PINOCCHIO_COMPILER_DIAGNOSTIC_PUSH
macros for pragma push/pop/ignore deprecated warnings
std::vector< Index > IndexVector
Matrix6x psid
psidot Derivative of Jacobian w.r.t to the parent body moving v(p(j)) x Sj
Matrix6x Ag
Centroidal Momentum Matrix.
VectorXs tmp
Temporary of size NV used in Cholesky Decomposition.
Eigen::Matrix< Scalar, 1, 6, Eigen::RowMajor|Options > Vector6r
std::vector< int > lastChild
Index of the last child (for CRBA)
std::vector< int > start_idx_v_fromRow
Starting index of the Joint motion subspace.
VectorXs Dinv
Diagonal inverse of the joint space intertia matrix obtained by a Cholesky Decomposition.
BodyRegressorType bodyRegressor
Body regressor.
JointCollectionTpl const Eigen::MatrixBase< ConfigVectorType > const Eigen::MatrixBase< TangentVectorType > & v
std::vector< std::vector< int > > supports_fromRow
Each element of this vector corresponds to the ordered list of indexes belonging to the supporting tr...
Matrix6x J
Jacobian of joint placements.
Scalar mechanical_energy
Mechanical energy of the system.
TangentVectorType dq_after
Generalized velocity after impact.
MotionTpl< Scalar, Options > Motion
Eigen::Matrix< Scalar, 6, 10, Options > BodyRegressorType
The type of the body regressor.
RowMatrixXs ddq_dq
Partial derivative of the joint acceleration vector with respect to the joint configuration.
Eigen::LLT< MatrixXs > llt_JMinvJt
Cholesky decompostion of .
Force hg
Centroidal momentum quantity.
Matrix6x dHdq
Variation of the spatial momenta set with respect to the joint configuration.
MatrixXs U
Joint space intertia matrix square root (upper trianglular part) computed with a Cholesky Decompositi...
VectorXs D
Diagonal of the joint space intertia matrix obtained by a Cholesky Decomposition.
VectorXs torque_residual
Temporary corresponding to the residual torque .
RowVectorXs potentialEnergyRegressor
Matrix related to potential energy regressor.
Eigen::Matrix< Scalar, 6, 6, Options > Matrix6
ForceTpl< Scalar, Options > Force
Eigen::Matrix< Scalar, 6, Eigen::Dynamic, Options > Matrix6x
The 6d jacobian type (temporary)
ModelTpl< Scalar, Options, JointCollectionTpl > Model
Common traits structure to fully define base classes for CRTP.
Matrix6x IS
Used in computeMinverse.
void computeParents_fromRow(const Model &model)
RowMatrixXs dtau_dv
Partial derivative of the joint torque vector with respect to the joint velocity.
Eigen::Matrix< Scalar, 1, Eigen::Dynamic, Options|Eigen::RowMajor > RowVectorXs
SE3Tpl< Scalar, Options > SE3
Matrix6x dVdq
Variation of the spatial velocity set with respect to the joint configuration.
MatrixXs osim
Operational space inertia matrix;.
VectorXs primal_dual_contact_solution
RHS vector when solving the contact dynamics KKT problem.
Inertia Ig
Centroidal Composite Rigid Body Inertia.
JointCollectionTpl< Scalar, Options > JointCollection
FrameTpl< Scalar, Options > Frame
VectorXs impulse_c
Lagrange Multipliers corresponding to the contact impulses in pinocchio::impulseDynamics.
JointCollectionTpl & model
ContactCholeskyDecomposition contact_chol
Cholesky decomposition of the KKT contact matrix.
Main pinocchio namespace.
VectorXs nle
Vector of Non Linear Effects (dim model.nv). It corresponds to concatenation of the Coriolis,...
Matrix6x dAdq
Variation of the spatial acceleration set with respect to the joint configuration.
pinocchio
Author(s):
autogenerated on Sun Nov 10 2024 03:42:56