6 #ifndef __pinocchio_multibody_data_hpp__
7 #define __pinocchio_multibody_data_hpp__
9 #include "pinocchio/spatial/fwd.hpp"
10 #include "pinocchio/math/tensor.hpp"
12 #include "pinocchio/spatial/se3.hpp"
13 #include "pinocchio/spatial/force.hpp"
14 #include "pinocchio/spatial/motion.hpp"
15 #include "pinocchio/spatial/inertia.hpp"
16 #include "pinocchio/multibody/fwd.hpp"
17 #include "pinocchio/multibody/joint/joint-generic.hpp"
18 #include "pinocchio/container/aligned-vector.hpp"
19 #include "pinocchio/algorithm/contact-cholesky.hpp"
21 #include "pinocchio/serialization/serializable.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>
36 typedef _Scalar Scalar;
39 template<
typename _Scalar,
int _Options,
template<
typename,
int>
class JointCollectionTpl>
42 ,
NumericalBase<DataTpl<_Scalar, _Options, JointCollectionTpl>>
44 EIGEN_MAKE_ALIGNED_OPERATOR_NEW
46 typedef _Scalar Scalar;
52 typedef JointCollectionTpl<Scalar, Options> JointCollection;
62 typedef pinocchio::Index Index;
63 typedef pinocchio::JointIndex JointIndex;
64 typedef pinocchio::GeomIndex GeomIndex;
65 typedef pinocchio::FrameIndex FrameIndex;
66 typedef std::vector<Index> IndexVector;
71 typedef PINOCCHIO_ALIGNED_STD_VECTOR(
JointModel) JointModelVector;
72 typedef PINOCCHIO_ALIGNED_STD_VECTOR(
JointData) JointDataVector;
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>
108 PINOCCHIO_COMPILER_DIAGNOSTIC_PUSH
109 PINOCCHIO_COMPILER_DIAGNOSTIC_IGNORED_DEPRECECATED_DECLARATIONS
111 PINOCCHIO_COMPILER_DIAGNOSTIC_POP
269 PINOCCHIO_ALIGNED_STD_VECTOR(Matrix6)
273 PINOCCHIO_ALIGNED_STD_VECTOR(Matrix6) oL;
276 PINOCCHIO_ALIGNED_STD_VECTOR(Matrix6) oK;
418 MatrixXs dlambda_dtau;
419 MatrixXs dlambda_dx_prox, drhs_prox;
422 PINOCCHIO_ALIGNED_STD_VECTOR(
SE3) iMf;
428 PINOCCHIO_ALIGNED_STD_VECTOR(Vector3) com;
434 PINOCCHIO_ALIGNED_STD_VECTOR(Vector3) vcom;
440 PINOCCHIO_ALIGNED_STD_VECTOR(Vector3) acom;
508 PINOCCHIO_ALIGNED_STD_VECTOR(
Matrix6x) KA;
509 PINOCCHIO_ALIGNED_STD_VECTOR(MatrixXs) LA;
510 PINOCCHIO_ALIGNED_STD_VECTOR(VectorXs) lA;
511 PINOCCHIO_ALIGNED_STD_VECTOR(VectorXs) lambdaA;
512 PINOCCHIO_ALIGNED_STD_VECTOR(
int) par_cons_ind;
513 PINOCCHIO_ALIGNED_STD_VECTOR(
Motion) a_bias;
514 PINOCCHIO_ALIGNED_STD_VECTOR(MatrixXs) KAS;
515 PINOCCHIO_ALIGNED_STD_VECTOR(
int) constraint_ind;
516 Eigen::LLT<MatrixXs> osim_llt;
518 #if defined(_MSC_VER)
521 #pragma warning(disable : 4554)
527 #if defined(_MSC_VER)
528 #pragma warning(default : 4554)
540 #if defined(_MSC_VER)
543 #pragma warning(disable : 4554)
564 #if defined(_MSC_VER)
565 #pragma warning(default : 4554)
568 PINOCCHIO_ALIGNED_STD_VECTOR(Matrix6)
569 extended_motion_propagator;
570 PINOCCHIO_ALIGNED_STD_VECTOR(Matrix6) extended_motion_propagator2;
571 PINOCCHIO_ALIGNED_STD_VECTOR(Matrix6) spatial_inv_inertia;
572 PINOCCHIO_ALIGNED_STD_VECTOR(
size_t) accumulation_descendant;
573 PINOCCHIO_ALIGNED_STD_VECTOR(
size_t) accumulation_ancestor;
574 PINOCCHIO_ALIGNED_STD_VECTOR(
int) constraints_supported_dim;
575 PINOCCHIO_ALIGNED_STD_VECTOR(std::set<size_t>) constraints_supported;
576 PINOCCHIO_ALIGNED_STD_VECTOR(
size_t) joints_supporting_constraints;
577 PINOCCHIO_ALIGNED_STD_VECTOR(
size_t) accumulation_joints;
578 PINOCCHIO_ALIGNED_STD_VECTOR(std::vector<size_t>) constraints_on_joint;
595 void computeLastChild(
const Model & model);
596 void computeParents_fromRow(
const Model & model);
597 void computeSupports_fromRow(
const Model & model);
605 #include "pinocchio/multibody/data.hxx"
607 #if PINOCCHIO_ENABLE_TEMPLATE_INSTANTIATION
608 #include "pinocchio/multibody/data.txx"
Main pinocchio namespace.
MatrixXs M
The joint space inertia matrix (a square matrix of dim model.nv).
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 al...
Tensor3x d2tau_dvdv
SO Partial derivative of the joint torque vector with respect to the joint velocity.
RowVectorXs kineticEnergyRegressor
Matrix related to kinetic energy regressor.
MatrixXs JMinvJt
Inverse of the operational-space inertia matrix.
Scalar potential_energy
Potential energy of the system.
Matrix6x dFda
Variation of the forceset with respect to the joint acceleration.
Inertia Ig
Centroidal Composite Rigid Body Inertia.
Matrix6x dFdv
Variation of the forceset with respect to the joint velocity.
Matrix6x IS
Used in computeMinverse.
MatrixXs osim
Operational space inertia matrix;.
PINOCCHIO_ALIGNED_STD_VECTOR(Motion) oa_gf
Vector of joint accelerations expressed at the origin of the world including the gravity contribution...
PINOCCHIO_ALIGNED_STD_VECTOR(Force) h
Vector of spatial momenta expressed in the local frame of the joint.
std::vector< int > nvSubtree
Dimension of the subtree motion space (for CRBA)
PINOCCHIO_ALIGNED_STD_VECTOR(Motion) a_gf
Vector of joint accelerations due to the gravity field.
VectorXs primal_rhs_contact
Primal RHS in contact dynamic equations.
VectorXs diff_lambda_c
Difference between two consecutive iterations of the proxy algorithm.
MatrixXs jointTorqueRegressor
Matrix related to joint torque regressor.
Scalar mechanical_energy
Mechanical energy of the system.
std::vector< int > lastChild
Index of the last child (for CRBA)
Matrix6x Ag
Centroidal Momentum Matrix.
PINOCCHIO_ALIGNED_STD_VECTOR(Inertia) Ycrb
Vector of sub-tree composite rigid body inertias, i.e. the apparent inertia of the subtree supported ...
TangentVectorType u
Intermediate quantity corresponding to apparent torque [ABA].
DataTpl()
Default constructor.
oYaba_contact
Articulated Body Inertia matrix with contact apparent inertia, of a given the subtree and expressed i...
VectorXs torque_residual
Temporary corresponding to the residual torque .
Tensor3x d2tau_dqdq
SO Partial derivative of the joint torque vector with respect to the joint configuration.
Tensor< Scalar, 3, Options > Tensor3x
 
Tensor3x d2tau_dqdv
SO Cross-Partial derivative of the joint torque vector with respect to the joint configuration/veloci...
Matrix6x dHdq
Variation of the spatial momenta set with respect to the joint configuration.
VectorXs lambda_c
Lagrange Multipliers corresponding to the contact forces in pinocchio::forwardDynamics.
PINOCCHIO_ALIGNED_STD_VECTOR(Matrix6) B
Combined variations of the inertia matrix consistent with Christoffel symbols.
MatrixXs dlambda_dq
Partial derivatives of the constraints forces with respect to the joint configuration,...
Tensor3x d2tau_dadq
SO Cross-Partial derivative of the joint torque vector with respect to the joint acceleration/configu...
RowMatrixXs dtau_dv
Partial derivative of the joint torque vector with respect to the joint velocity.
PINOCCHIO_ALIGNED_STD_VECTOR(Matrix6) dYcrb
Vector of sub-tree composite rigid body inertia time derivatives . See Data::Ycrb for more details.
VectorXs Dinv
Diagonal inverse of the joint space intertia matrix obtained by a Cholesky Decomposition.
VectorXs D
Diagonal of the joint space intertia matrix obtained by a Cholesky Decomposition.
VectorXs impulse_c
Lagrange Multipliers corresponding to the contact impulses in pinocchio::impulseDynamics.
Matrix6x dAdv
Variation of the spatial acceleration set with respect to the joint velocity.
std::vector< int > end_idx_v_fromRow
End index of the Joint motion subspace.
PINOCCHIO_ALIGNED_STD_VECTOR(Force) oh
Vector of spatial momenta expressed at the origin of the world.
Matrix6x dVdq
Variation of the spatial velocity set with respect to the joint configuration.
Matrix6 Itmp
Temporary for derivative algorithms.
PINOCCHIO_ALIGNED_STD_VECTOR(Motion) v
Vector of joint velocities expressed in the local frame of the joint.
VectorXs g
Vector of generalized gravity (dim model.nv).
PINOCCHIO_ALIGNED_STD_VECTOR(Matrix6) oYaba
Articulated Body Inertia matrix of the subtree expressed in the WORLD coordinate frame.
MatrixXs sDUiJt
Temporary corresponding to .
DataTpl(const Model &model)
Default constructor of pinocchio::Data from a pinocchio::Model.
PINOCCHIO_ALIGNED_STD_VECTOR(Motion) oa
Vector of joint accelerations expressed at the origin of the world.
VectorXs TangentVectorType
Dense vectorized version of a joint tangent vector (e.g. velocity, acceleration, etc)....
VectorXs lambda_c_prox
Proximal Lagrange Multipliers used in the computation of the Forward Dynamics computations.
std::vector< int > parents_fromRow
First previous non-zero row in M (used in Cholesky Decomposition).
TangentVectorType tau
Vector of joint torques (dim model.nv).
PINOCCHIO_ALIGNED_STD_VECTOR(SE3) liMi
Vector of relative joint placements (wrt the body parent).
Eigen::LLT< MatrixXs > llt_JMinvJt
Cholesky decompostion of .
Eigen::Matrix< Scalar, 6, 10, Options > BodyRegressorType
The type of the body regressor.
Eigen::Matrix< Scalar, 6, Eigen::Dynamic, Options > Matrix6x
The 6d jacobian type (temporary)
PINOCCHIO_ALIGNED_STD_VECTOR(Inertia) oinertias
Rigid Body Inertia supported by the joint expressed in the world frame.
Matrix6x dFdq
Variation of the forceset with respect to the joint configuration.
Matrix3x Jcom
Jacobian of center of mass.
RowMatrixXs ddq_dtau
Partial derivative of the joint acceleration vector with respect to the joint torques.
RowVectorXs potentialEnergyRegressor
Matrix related to potential energy regressor.
PINOCCHIO_ALIGNED_STD_VECTOR(Motion) oa_drift
Vector of joint accelerations expressed at the origin of the world. These accelerations are used in t...
RowMatrixXs ddq_dv
Partial derivative of the joint acceleration vector with respect to the joint velocity.
std::vector< int > nvSubtree_fromRow
Subtree of the current row index (used in Cholesky Decomposition).
TangentVectorType ddq
The joint accelerations computed from ABA.
std::vector< std::vector< int > > supports_fromRow
Each element of this vector corresponds to the ordered list of indexes belonging to the supporting tr...
PINOCCHIO_ALIGNED_STD_VECTOR(SE3) oMi
Vector of absolute joint placements (wrt the world).
TangentVectorType dq_after
Generalized velocity after impact.
RowMatrixXs dtau_dq
Partial derivative of the joint torque vector with respect to the joint configuration.
MatrixXs dvc_dq
Stack of partial derivative of the contact frame acceleration with respect to the joint parameters.
MatrixXs U
Joint space intertia matrix square root (upper trianglular part) computed with a Cholesky Decompositi...
Force hg
Centroidal momentum quantity.
PINOCCHIO_ALIGNED_STD_VECTOR(Matrix6) doYcrb
Time variation of Composite Rigid Body Inertia expressed in the world frame.
Scalar kinetic_energy
Kinetic energy of the system.
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
Matrix6x SDinv
Used in computeMinverse.
Tensor3x kinematic_hessians
Tensor containing the kinematic Hessian of all the joints.
PINOCCHIO_ALIGNED_STD_VECTOR(Force) f
Vector of body forces expressed in the local frame of the joint. For each body, the force represents ...
PINOCCHIO_ALIGNED_STD_VECTOR(Matrix6) Ivx
Left variation of the inertia matrix.
Matrix6 M6tmp
Temporary for derivative algorithms.
ContactCholeskyDecomposition contact_chol
Cholesky decomposition of the KKT contact matrix.
PINOCCHIO_COMPILER_DIAGNOSTIC_POP JointDataVector joints
Vector of pinocchio::JointData associated to the pinocchio::JointModel stored in model,...
std::vector< Scalar > mass
Vector of subtree mass. In other words, mass[j] is the mass of the subtree supported by joint ....
Matrix6x dAg
Centroidal Momentum Matrix Time Variation.
VectorXs primal_dual_contact_solution
RHS vector when solving the contact dynamics KKT problem.
PINOCCHIO_ALIGNED_STD_VECTOR(Motion) ov
Vector of joint velocities expressed at the origin of the world.
Force dhg
Centroidal momentum time derivative.
Matrix6x J
Jacobian of joint placements.
Matrix6x psid
psidot Derivative of Jacobian w.r.t to the parent body moving v(p(j)) x Sj
RowMatrixXs Minv
The inverse of the joint space inertia matrix (a square matrix of dim model.nv).
VectorXs nle
Vector of Non Linear Effects (dim model.nv). It corresponds to concatenation of the Coriolis,...
Eigen::Matrix< Scalar, 3, Eigen::Dynamic, Options > Matrix3x
The 3d jacobian type (temporary)
PINOCCHIO_ALIGNED_STD_VECTOR(Force) of
Vector of body forces expressed at the origin of the world. For each body, the force represents the s...
Matrix6x dJ
Derivative of the Jacobian with respect to the time.
MatrixXs C
The Coriolis matrix (a square matrix of dim model.nv).
VectorXs ConfigVectorType
Dense vectorized version of a joint configuration vector.
PINOCCHIO_ALIGNED_STD_VECTOR(Motion) oa_augmented
Vector of joint accelerations expressed at the origin of the world. These accelerations are used in t...
std::vector< int > start_idx_v_fromRow
Starting index of the Joint motion subspace.
VectorXs tmp
Temporary of size NV used in Cholesky Decomposition.
PINOCCHIO_ALIGNED_STD_VECTOR(Motion) a
Vector of joint accelerations expressed in the local frame of the joint.
PINOCCHIO_ALIGNED_STD_VECTOR(SE3) oMf
Vector of absolute operationnel frame placements (wrt the world).
Matrix6x UDinv
Used in computeMinverse.
RowMatrixXs ddq_dq
Partial derivative of the joint acceleration vector with respect to the joint configuration.
Matrix3x staticRegressor
Matrix related to static regressor.
BodyRegressorType bodyRegressor
Body regressor.
PINOCCHIO_ALIGNED_STD_VECTOR(Matrix6) vxI
Right variation of the inertia matrix.
PINOCCHIO_ALIGNED_STD_VECTOR(Matrix6) Yaba
Articulated Body Inertia matrix of the subtree expressed in the LOCAL coordinate frame of the joint.
Matrix6x ddJ
Second derivative of the Jacobian with respect to the time.
Matrix6x dAdq
Variation of the spatial acceleration set with respect to the joint configuration.
PINOCCHIO_ALIGNED_STD_VECTOR(Inertia) oYcrb
Composite Rigid Body Inertia expressed in the world frame.
A Plucker coordinate frame attached to a parent joint inside a kinematic tree.
Common traits structure to fully define base classes for CRTP.