pinocchio  3.3.0
A fast and flexible implementation of Rigid Body Dynamics algorithms and their analytical derivatives
data.hpp
1 //
2 // Copyright (c) 2015-2024 CNRS INRIA
3 // Copyright (c) 2015 Wandercraft, 86 rue de Paris 91400 Orsay, France.
4 //
5 
6 #ifndef __pinocchio_multibody_data_hpp__
7 #define __pinocchio_multibody_data_hpp__
8 
9 #include "pinocchio/spatial/fwd.hpp"
10 #include "pinocchio/math/tensor.hpp"
11 
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"
20 
21 #include "pinocchio/serialization/serializable.hpp"
22 
23 #include <Eigen/Cholesky>
24 #include <Eigen/StdVector>
25 #include <Eigen/src/Core/util/Constants.h>
26 
27 #include <cstddef>
28 #include <set>
29 
30 namespace pinocchio
31 {
32 
33  template<typename _Scalar, int _Options, template<typename, int> class JointCollectionTpl>
34  struct traits<DataTpl<_Scalar, _Options, JointCollectionTpl>>
35  {
36  typedef _Scalar Scalar;
37  };
38 
39  template<typename _Scalar, int _Options, template<typename, int> class JointCollectionTpl>
40  struct DataTpl
41  : serialization::Serializable<DataTpl<_Scalar, _Options, JointCollectionTpl>>
42  , NumericalBase<DataTpl<_Scalar, _Options, JointCollectionTpl>>
43  {
44  EIGEN_MAKE_ALIGNED_OPERATOR_NEW
45 
46  typedef _Scalar Scalar;
47  enum
48  {
49  Options = _Options
50  };
51 
52  typedef JointCollectionTpl<Scalar, Options> JointCollection;
53 
55 
61 
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;
67 
70 
71  typedef PINOCCHIO_ALIGNED_STD_VECTOR(JointModel) JointModelVector;
72  typedef PINOCCHIO_ALIGNED_STD_VECTOR(JointData) JointDataVector;
73 
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;
79 
80  typedef Eigen::Matrix<Scalar, 6, 1, Options> Vector6c;
81  typedef Eigen::Matrix<Scalar, 1, 6, Eigen::RowMajor | Options> Vector6r;
82 
84  typedef VectorXs ConfigVectorType;
85 
89  typedef VectorXs TangentVectorType;
90 
92  typedef Eigen::Matrix<Scalar, 6, Eigen::Dynamic, Options> Matrix6x;
94  typedef Eigen::Matrix<Scalar, 3, Eigen::Dynamic, Options> Matrix3x;
95 
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>
99  RowMatrixXs;
100 
102  typedef Eigen::Matrix<Scalar, 6, 10, Options> BodyRegressorType;
103 
106 
107  // TODO Remove when API is stabilized
108  PINOCCHIO_COMPILER_DIAGNOSTIC_PUSH
109  PINOCCHIO_COMPILER_DIAGNOSTIC_IGNORED_DEPRECECATED_DECLARATIONS
111  PINOCCHIO_COMPILER_DIAGNOSTIC_POP
112 
115  JointDataVector joints;
116 
119 
122 
126 
130 
133 
137 
140 
143 
148 
153 
159 
162 
165 
168 
171 
174 
179  VectorXs nle;
180 
184  VectorXs g;
185 
188 
193 
196  PINOCCHIO_ALIGNED_STD_VECTOR(Matrix6) dYcrb; // TODO: change with dense symmetric matrix6
197 
199  MatrixXs M;
200 
202  RowMatrixXs Minv;
203 
205  MatrixXs C;
206 
209 
212 
215 
218 
221 
224 
227 
230 
233 
237 
240 
243 
246 
248  Matrix6 Itmp;
249 
251  Matrix6 M6tmp;
252  RowMatrix6 M6tmpR;
253  RowMatrix6 M6tmpR2;
254 
257 
258  // ABA internal data
261  PINOCCHIO_ALIGNED_STD_VECTOR(Matrix6) Yaba; // TODO: change with dense symmetric matrix6
262 
265  PINOCCHIO_ALIGNED_STD_VECTOR(Matrix6) oYaba; // TODO: change with dense symmetric matrix6
266 
269  PINOCCHIO_ALIGNED_STD_VECTOR(Matrix6)
270  oYaba_contact; // TODO: change with dense symmetric matrix6
271 
273  PINOCCHIO_ALIGNED_STD_VECTOR(Matrix6) oL; // TODO: change with dense symmetric matrix6
274 
276  PINOCCHIO_ALIGNED_STD_VECTOR(Matrix6) oK; // TODO: change with dense symmetric matrix6
277 
279  TangentVectorType u; // Joint Inertia
280 
281  // CCRBA return quantities
285 
286  // dCCRBA return quantities
291 
298 
306 
311 
313  PINOCCHIO_ALIGNED_STD_VECTOR(Matrix6x) Fcrb;
314 
316  std::vector<int> lastChild;
317 
319  std::vector<int> nvSubtree;
320 
322  std::vector<int> start_idx_v_fromRow;
323 
325  std::vector<int> end_idx_v_fromRow;
326 
329  MatrixXs U;
330 
332  VectorXs D;
333 
336  VectorXs Dinv;
337 
339  VectorXs tmp;
340 
342  std::vector<int> parents_fromRow;
343 
348  std::vector<std::vector<int>> supports_fromRow;
349 
351  std::vector<int> nvSubtree_fromRow;
352 
361 
364 
367 
371 
375 
378 
381 
384 
387  RowMatrixXs dtau_dq;
388 
390  RowMatrixXs dtau_dv;
391 
394  RowMatrixXs ddq_dq;
395 
398  RowMatrixXs ddq_dv;
399 
402  RowMatrixXs ddq_dtau;
403 
406  MatrixXs dvc_dq;
407  MatrixXs dac_dq;
408  MatrixXs dac_dv;
409  MatrixXs dac_da;
410 
412  MatrixXs osim;
413 
416  MatrixXs dlambda_dq;
417  MatrixXs dlambda_dv;
418  MatrixXs dlambda_dtau;
419  MatrixXs dlambda_dx_prox, drhs_prox;
420 
422  PINOCCHIO_ALIGNED_STD_VECTOR(SE3) iMf;
423 
428  PINOCCHIO_ALIGNED_STD_VECTOR(Vector3) com;
429 
434  PINOCCHIO_ALIGNED_STD_VECTOR(Vector3) vcom;
435 
440  PINOCCHIO_ALIGNED_STD_VECTOR(Vector3) acom;
441 
444  std::vector<Scalar> mass;
445 
451 
454 
457 
460 
461  // Temporary variables used in forward dynamics
462 
464  MatrixXs JMinvJt;
465 
467  Eigen::LLT<MatrixXs> llt_JMinvJt;
468 
471  VectorXs lambda_c;
472 
475  VectorXs lambda_c_prox;
476 
478  VectorXs diff_lambda_c;
479 
481  MatrixXs sDUiJt;
482 
484  VectorXs torque_residual;
485 
488 
491  VectorXs impulse_c;
492 
495 
498 
501 
504 
507 
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;
517 
518 #if defined(_MSC_VER)
519  // Eigen tensor warning: Eigen\CXX11\src/Tensor/Tensor.h(76,1): warning C4554: '&': check
520  // operator precedence for possible error
521  #pragma warning(disable : 4554)
522 #endif
523 
526 
527 #if defined(_MSC_VER)
528  #pragma warning(default : 4554) // C4554 enabled after tensor definition
529 #endif
530 
533 
536 
539 
540 #if defined(_MSC_VER)
541  // Eigen tensor warning: Eigen\CXX11\src/Tensor/Tensor.h(76,1): warning C4554: '&': check
542  // operator precedence for possible error
543  #pragma warning(disable : 4554)
544 #endif
545 
549 
553 
557 
563 
564 #if defined(_MSC_VER)
565  #pragma warning(default : 4554) // C4554 enabled after tensor definition
566 #endif
567 
568  PINOCCHIO_ALIGNED_STD_VECTOR(Matrix6)
569  extended_motion_propagator; // Stores force propagator to the base link
570  PINOCCHIO_ALIGNED_STD_VECTOR(Matrix6) extended_motion_propagator2;
571  PINOCCHIO_ALIGNED_STD_VECTOR(Matrix6) spatial_inv_inertia; // Stores spatial inverse 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;
579 
585  explicit DataTpl(const Model & model);
586 
591  {
592  }
593 
594  private:
595  void computeLastChild(const Model & model);
596  void computeParents_fromRow(const Model & model);
597  void computeSupports_fromRow(const Model & model);
598  };
599 
600 } // namespace pinocchio
601 
602 /* --- Details -------------------------------------------------------------- */
603 /* --- Details -------------------------------------------------------------- */
604 /* --- Details -------------------------------------------------------------- */
605 #include "pinocchio/multibody/data.hxx"
606 
607 #if PINOCCHIO_ENABLE_TEMPLATE_INSTANTIATION
608  #include "pinocchio/multibody/data.txx"
609 #endif // PINOCCHIO_ENABLE_TEMPLATE_INSTANTIATION
610 
611 #endif // ifndef __pinocchio_multibody_data_hpp__
Main pinocchio namespace.
Definition: treeview.dox:11
MatrixXs M
The joint space inertia matrix (a square matrix of dim model.nv).
Definition: data.hpp:199
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.
Definition: data.hpp:552
RowVectorXs kineticEnergyRegressor
Matrix related to kinetic energy regressor.
Definition: data.hpp:503
MatrixXs JMinvJt
Inverse of the operational-space inertia matrix.
Definition: data.hpp:464
Scalar potential_energy
Potential energy of the system.
Definition: data.hpp:456
Matrix6x dFda
Variation of the forceset with respect to the joint acceleration.
Definition: data.hpp:217
Inertia Ig
Centroidal Composite Rigid Body Inertia.
Definition: data.hpp:310
Matrix6x dFdv
Variation of the forceset with respect to the joint velocity.
Definition: data.hpp:214
Matrix6x IS
Used in computeMinverse.
Definition: data.hpp:226
MatrixXs osim
Operational space inertia matrix;.
Definition: data.hpp:412
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)
Definition: data.hpp:319
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.
Definition: data.hpp:538
VectorXs diff_lambda_c
Difference between two consecutive iterations of the proxy algorithm.
Definition: data.hpp:478
MatrixXs jointTorqueRegressor
Matrix related to joint torque regressor.
Definition: data.hpp:500
Scalar mechanical_energy
Mechanical energy of the system.
Definition: data.hpp:459
std::vector< int > lastChild
Index of the last child (for CRBA)
Definition: data.hpp:316
Matrix6x Ag
Centroidal Momentum Matrix.
Definition: data.hpp:284
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].
Definition: data.hpp:279
DataTpl()
Default constructor.
Definition: data.hpp:590
oYaba_contact
Articulated Body Inertia matrix with contact apparent inertia, of a given the subtree and expressed i...
Definition: data.hpp:270
VectorXs torque_residual
Temporary corresponding to the residual torque .
Definition: data.hpp:484
Tensor3x d2tau_dqdq
SO Partial derivative of the joint torque vector with respect to the joint configuration.
Definition: data.hpp:548
Tensor< Scalar, 3, Options > Tensor3x
&#160;
Definition: data.hpp:105
Tensor3x d2tau_dqdv
SO Cross-Partial derivative of the joint torque vector with respect to the joint configuration/veloci...
Definition: data.hpp:556
Matrix6x dHdq
Variation of the spatial momenta set with respect to the joint configuration.
Definition: data.hpp:208
VectorXs lambda_c
Lagrange Multipliers corresponding to the contact forces in pinocchio::forwardDynamics.
Definition: data.hpp:471
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,...
Definition: data.hpp:416
Tensor3x d2tau_dadq
SO Cross-Partial derivative of the joint torque vector with respect to the joint acceleration/configu...
Definition: data.hpp:562
RowMatrixXs dtau_dv
Partial derivative of the joint torque vector with respect to the joint velocity.
Definition: data.hpp:390
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.
Definition: data.hpp:336
VectorXs D
Diagonal of the joint space intertia matrix obtained by a Cholesky Decomposition.
Definition: data.hpp:332
VectorXs impulse_c
Lagrange Multipliers corresponding to the contact impulses in pinocchio::impulseDynamics.
Definition: data.hpp:491
Matrix6x dAdv
Variation of the spatial acceleration set with respect to the joint velocity.
Definition: data.hpp:383
std::vector< int > end_idx_v_fromRow
End index of the Joint motion subspace.
Definition: data.hpp:325
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.
Definition: data.hpp:377
Matrix6 Itmp
Temporary for derivative algorithms.
Definition: data.hpp:248
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).
Definition: data.hpp:184
PINOCCHIO_ALIGNED_STD_VECTOR(Matrix6) oYaba
Articulated Body Inertia matrix of the subtree expressed in the WORLD coordinate frame.
MatrixXs sDUiJt
Temporary corresponding to .
Definition: data.hpp:481
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)....
Definition: data.hpp:89
VectorXs lambda_c_prox
Proximal Lagrange Multipliers used in the computation of the Forward Dynamics computations.
Definition: data.hpp:475
std::vector< int > parents_fromRow
First previous non-zero row in M (used in Cholesky Decomposition).
Definition: data.hpp:342
TangentVectorType tau
Vector of joint torques (dim model.nv).
Definition: data.hpp:173
PINOCCHIO_ALIGNED_STD_VECTOR(SE3) liMi
Vector of relative joint placements (wrt the body parent).
Eigen::LLT< MatrixXs > llt_JMinvJt
Cholesky decompostion of .
Definition: data.hpp:467
Eigen::Matrix< Scalar, 6, 10, Options > BodyRegressorType
The type of the body regressor.
Definition: data.hpp:102
Eigen::Matrix< Scalar, 6, Eigen::Dynamic, Options > Matrix6x
The 6d jacobian type (temporary)
Definition: data.hpp:92
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.
Definition: data.hpp:211
Matrix3x Jcom
Jacobian of center of mass.
Definition: data.hpp:450
RowMatrixXs ddq_dtau
Partial derivative of the joint acceleration vector with respect to the joint torques.
Definition: data.hpp:402
RowVectorXs potentialEnergyRegressor
Matrix related to potential energy regressor.
Definition: data.hpp:506
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.
Definition: data.hpp:398
std::vector< int > nvSubtree_fromRow
Subtree of the current row index (used in Cholesky Decomposition).
Definition: data.hpp:351
TangentVectorType ddq
The joint accelerations computed from ABA.
Definition: data.hpp:256
std::vector< std::vector< int > > supports_fromRow
Each element of this vector corresponds to the ordered list of indexes belonging to the supporting tr...
Definition: data.hpp:348
PINOCCHIO_ALIGNED_STD_VECTOR(SE3) oMi
Vector of absolute joint placements (wrt the world).
TangentVectorType dq_after
Generalized velocity after impact.
Definition: data.hpp:487
RowMatrixXs dtau_dq
Partial derivative of the joint torque vector with respect to the joint configuration.
Definition: data.hpp:387
MatrixXs dvc_dq
Stack of partial derivative of the contact frame acceleration with respect to the joint parameters.
Definition: data.hpp:406
MatrixXs U
Joint space intertia matrix square root (upper trianglular part) computed with a Cholesky Decompositi...
Definition: data.hpp:329
Force hg
Centroidal momentum quantity.
Definition: data.hpp:297
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.
Definition: data.hpp:453
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
Definition: data.hpp:374
Matrix6x SDinv
Used in computeMinverse.
Definition: data.hpp:220
Tensor3x kinematic_hessians
Tensor containing the kinematic Hessian of all the joints.
Definition: data.hpp:525
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.
Definition: data.hpp:251
ContactCholeskyDecomposition contact_chol
Cholesky decomposition of the KKT contact matrix.
Definition: data.hpp:532
PINOCCHIO_COMPILER_DIAGNOSTIC_POP JointDataVector joints
Vector of pinocchio::JointData associated to the pinocchio::JointModel stored in model,...
Definition: data.hpp:115
std::vector< Scalar > mass
Vector of subtree mass. In other words, mass[j] is the mass of the subtree supported by joint ....
Definition: data.hpp:444
Matrix6x dAg
Centroidal Momentum Matrix Time Variation.
Definition: data.hpp:290
VectorXs primal_dual_contact_solution
RHS vector when solving the contact dynamics KKT problem.
Definition: data.hpp:535
PINOCCHIO_ALIGNED_STD_VECTOR(Motion) ov
Vector of joint velocities expressed at the origin of the world.
Force dhg
Centroidal momentum time derivative.
Definition: data.hpp:305
Matrix6x J
Jacobian of joint placements.
Definition: data.hpp:360
Matrix6x psid
psidot Derivative of Jacobian w.r.t to the parent body moving v(p(j)) x Sj
Definition: data.hpp:370
RowMatrixXs Minv
The inverse of the joint space inertia matrix (a square matrix of dim model.nv).
Definition: data.hpp:202
VectorXs nle
Vector of Non Linear Effects (dim model.nv). It corresponds to concatenation of the Coriolis,...
Definition: data.hpp:179
Eigen::Matrix< Scalar, 3, Eigen::Dynamic, Options > Matrix3x
The 3d jacobian type (temporary)
Definition: data.hpp:94
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.
Definition: data.hpp:363
MatrixXs C
The Coriolis matrix (a square matrix of dim model.nv).
Definition: data.hpp:205
VectorXs ConfigVectorType
Dense vectorized version of a joint configuration vector.
Definition: data.hpp:84
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.
Definition: data.hpp:322
VectorXs tmp
Temporary of size NV used in Cholesky Decomposition.
Definition: data.hpp:339
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.
Definition: data.hpp:223
RowMatrixXs ddq_dq
Partial derivative of the joint acceleration vector with respect to the joint configuration.
Definition: data.hpp:394
Matrix3x staticRegressor
Matrix related to static regressor.
Definition: data.hpp:494
BodyRegressorType bodyRegressor
Body regressor.
Definition: data.hpp:497
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.
Definition: data.hpp:366
Matrix6x dAdq
Variation of the spatial acceleration set with respect to the joint configuration.
Definition: data.hpp:380
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.
Definition: frame.hpp:56
Common traits structure to fully define base classes for CRTP.
Definition: fwd.hpp:72