pinocchio  2.7.0
A fast and flexible implementation of Rigid Body Dynamics algorithms and their analytical derivatives
data.hpp
1 //
2 // Copyright (c) 2015-2022 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/math/tensor.hpp"
10 
11 #include "pinocchio/spatial/fwd.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 
20 #include "pinocchio/serialization/serializable.hpp"
21 
22 #include <iostream>
23 #include <Eigen/Cholesky>
24 
25 namespace pinocchio
26 {
27 
28  template<typename _Scalar, int _Options, template<typename,int> class JointCollectionTpl>
29  struct DataTpl
30  : serialization::Serializable< DataTpl<_Scalar,_Options,JointCollectionTpl> >
31  {
32  EIGEN_MAKE_ALIGNED_OPERATOR_NEW
33 
34  typedef _Scalar Scalar;
35  enum { Options = _Options };
36 
37  typedef JointCollectionTpl<Scalar,Options> JointCollection;
38 
40 
46 
47  typedef pinocchio::Index Index;
48  typedef pinocchio::JointIndex JointIndex;
49  typedef pinocchio::GeomIndex GeomIndex;
50  typedef pinocchio::FrameIndex FrameIndex;
51  typedef std::vector<Index> IndexVector;
52 
55 
56  typedef PINOCCHIO_ALIGNED_STD_VECTOR(JointModel) JointModelVector;
57  typedef PINOCCHIO_ALIGNED_STD_VECTOR(JointData) JointDataVector;
58 
59  typedef Eigen::Matrix<Scalar,Eigen::Dynamic,Eigen::Dynamic,Options> MatrixXs;
60  typedef Eigen::Matrix<Scalar,Eigen::Dynamic,1,Options> VectorXs;
61  typedef Eigen::Matrix<Scalar,3,1,Options> Vector3;
62  typedef Eigen::Matrix<Scalar, 6, 1, Options> Vector6c;
63  typedef Eigen::Matrix<Scalar, 1, 6, Eigen::RowMajor | Options> Vector6r;
64 
66  typedef VectorXs ConfigVectorType;
67 
70  typedef VectorXs TangentVectorType;
71 
73  typedef Eigen::Matrix<Scalar,6,Eigen::Dynamic,Options> Matrix6x;
75  typedef Eigen::Matrix<Scalar,3,Eigen::Dynamic,Options> Matrix3x;
76 
77  typedef Eigen::Matrix<Scalar,6,6,Options> Matrix6;
78  typedef Eigen::Matrix<Scalar,6,6,Eigen::RowMajor | Options> RowMatrix6;
79  typedef Eigen::Matrix<Scalar,Eigen::Dynamic,Eigen::Dynamic,Eigen::RowMajor | Options> RowMatrixXs;
80 
82  typedef Eigen::Matrix<Scalar,6,10,Options> BodyRegressorType;
83 
86 
89  JointDataVector joints;
90 
92  PINOCCHIO_ALIGNED_STD_VECTOR(Motion) a;
93 
95  PINOCCHIO_ALIGNED_STD_VECTOR(Motion) oa;
96 
98  PINOCCHIO_ALIGNED_STD_VECTOR(Motion) a_gf;
99 
101  PINOCCHIO_ALIGNED_STD_VECTOR(Motion) oa_gf;
102 
104  PINOCCHIO_ALIGNED_STD_VECTOR(Motion) v;
105 
107  PINOCCHIO_ALIGNED_STD_VECTOR(Motion) ov;
108 
111  PINOCCHIO_ALIGNED_STD_VECTOR(Force) f;
112 
115  PINOCCHIO_ALIGNED_STD_VECTOR(Force) of;
116 
118  PINOCCHIO_ALIGNED_STD_VECTOR(Force) h;
119 
121  PINOCCHIO_ALIGNED_STD_VECTOR(Force) oh;
122 
124  PINOCCHIO_ALIGNED_STD_VECTOR(SE3) oMi;
125 
127  PINOCCHIO_ALIGNED_STD_VECTOR(SE3) liMi;
128 
131 
135  VectorXs nle;
136 
140  VectorXs g;
141 
143  PINOCCHIO_ALIGNED_STD_VECTOR(SE3) oMf;
144 
147  PINOCCHIO_ALIGNED_STD_VECTOR(Inertia) Ycrb;
148 
150  PINOCCHIO_ALIGNED_STD_VECTOR(Matrix6) dYcrb; // TODO: change with dense symmetric matrix6
151 
153  MatrixXs M;
154 
156  RowMatrixXs Minv;
157 
159  MatrixXs C;
160 
163 
166 
169 
172 
175 
178 
181 
183  PINOCCHIO_ALIGNED_STD_VECTOR(Matrix6) vxI;
184 
186  PINOCCHIO_ALIGNED_STD_VECTOR(Matrix6) Ivx;
187 
189  PINOCCHIO_ALIGNED_STD_VECTOR(Matrix6) B;
190 
192  PINOCCHIO_ALIGNED_STD_VECTOR(Inertia) oinertias;
193 
195  PINOCCHIO_ALIGNED_STD_VECTOR(Inertia) oYcrb;
196 
198  PINOCCHIO_ALIGNED_STD_VECTOR(Matrix6) doYcrb;
199 
201  Matrix6 Itmp;
202 
204  Matrix6 M6tmp;
205  RowMatrix6 M6tmpR;
206  RowMatrix6 M6tmpR2;
207 
210 
211  // ABA internal data
213  PINOCCHIO_ALIGNED_STD_VECTOR(Matrix6) Yaba; // TODO: change with dense symmetric matrix6
214 
216  TangentVectorType u; // Joint Inertia
217 
218  // CCRBA return quantities
222 
223  // dCCRBA return quantities
227 
233 
239 
243 
245  PINOCCHIO_ALIGNED_STD_VECTOR(Matrix6x) Fcrb;
246 
248  std::vector<int> lastChild;
249 
251  std::vector<int> nvSubtree;
252 
254  std::vector<int> start_idx_v_fromRow;
255 
257  std::vector<int> end_idx_v_fromRow;
258 
260  MatrixXs U;
261 
263  VectorXs D;
264 
266  VectorXs Dinv;
267 
269  VectorXs tmp;
270 
272  std::vector<int> parents_fromRow;
273 
276  std::vector< std::vector<int> > supports_fromRow;
277 
279  std::vector<int> nvSubtree_fromRow;
280 
284 
287 
290 
294 
298 
301 
304 
307 
309  MatrixXs dtau_dq;
310 
312  MatrixXs dtau_dv;
313 
315  MatrixXs ddq_dq;
316 
318  MatrixXs ddq_dv;
319 
321  PINOCCHIO_ALIGNED_STD_VECTOR(SE3) iMf;
322 
324  PINOCCHIO_ALIGNED_STD_VECTOR(Vector3) com;
325 
327  PINOCCHIO_ALIGNED_STD_VECTOR(Vector3) vcom;
328 
330  PINOCCHIO_ALIGNED_STD_VECTOR(Vector3) acom;
331 
333  std::vector<Scalar> mass;
334 
338 
341 
344 
345  // Temporary variables used in forward dynamics
346 
348  MatrixXs JMinvJt;
349 
351  Eigen::LLT<MatrixXs> llt_JMinvJt;
352 
354  VectorXs lambda_c;
355 
357  MatrixXs sDUiJt;
358 
360  VectorXs torque_residual;
361 
364 
366  VectorXs impulse_c;
367 
370 
373 
376 
379 
383 
387 
391 
397 
403  explicit DataTpl(const Model & model);
404 
408  DataTpl() {}
409 
410  private:
411  void computeLastChild(const Model & model);
412  void computeParents_fromRow(const Model & model);
413  void computeSupports_fromRow(const Model & model);
414 
415  };
416 
417 } // namespace pinocchio
418 
419 /* --- Details -------------------------------------------------------------- */
420 /* --- Details -------------------------------------------------------------- */
421 /* --- Details -------------------------------------------------------------- */
422 #include "pinocchio/multibody/data.hxx"
423 
424 #endif // ifndef __pinocchio_multibody_data_hpp__
425 
pinocchio::DataTpl::DataTpl
DataTpl()
Default constructor.
Definition: data.hpp:408
pinocchio::DataTpl::lambda_c
VectorXs lambda_c
Lagrange Multipliers corresponding to the contact forces in pinocchio::forwardDynamics.
Definition: data.hpp:354
pinocchio::DataTpl::tmp
VectorXs tmp
Temporary of size NV used in Cholesky Decomposition.
Definition: data.hpp:269
pinocchio::DataTpl::bodyRegressor
BodyRegressorType bodyRegressor
Body regressor.
Definition: data.hpp:372
pinocchio::DataTpl
Definition: data.hpp:29
pinocchio::DataTpl::Ag
Matrix6x Ag
Centroidal Momentum Matrix.
Definition: data.hpp:221
pinocchio::DataTpl::supports_fromRow
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:276
pinocchio::DataTpl::Tensor3x
Tensor< Scalar, 3, Options > Tensor3x
&#160;
Definition: data.hpp:85
pinocchio::DataTpl::Jcom
Matrix3x Jcom
Jacobian of center of mass.
Definition: data.hpp:337
pinocchio::DataTpl::dAg
Matrix6x dAg
Centroidal Momentum Matrix Time Variation.
Definition: data.hpp:226
pinocchio::DataTpl::d2tau_dadq
Tensor3x d2tau_dadq
SO Cross-Partial derivative of the joint torque vector with respect to the joint acceleration/configu...
Definition: data.hpp:396
pinocchio::DataTpl::tau
TangentVectorType tau
Vector of joint torques (dim model.nv).
Definition: data.hpp:130
pinocchio::DataTpl::jointTorqueRegressor
MatrixXs jointTorqueRegressor
Matrix related to joint torque regressor.
Definition: data.hpp:375
pinocchio::SE3Tpl< Scalar, Options >
pinocchio::DataTpl::u
TangentVectorType u
Intermediate quantity corresponding to apparent torque [ABA].
Definition: data.hpp:216
pinocchio::DataTpl::torque_residual
VectorXs torque_residual
Temporary corresponding to the residual torque .
Definition: data.hpp:360
pinocchio::DataTpl::dJ
Matrix6x dJ
Derivative of the Jacobian with respect to the time.
Definition: data.hpp:286
pinocchio::DataTpl::ddJ
Matrix6x ddJ
Second derivative of the Jacobian with respect to the time.
Definition: data.hpp:289
pinocchio::DataTpl::dAdv
Matrix6x dAdv
Variation of the spatial acceleration set with respect to the joint velocity.
Definition: data.hpp:306
pinocchio::JointDataTpl
Definition: fwd.hpp:97
pinocchio::DataTpl::nvSubtree_fromRow
std::vector< int > nvSubtree_fromRow
Subtree of the current row index (used in Cholesky Decomposition).
Definition: data.hpp:279
pinocchio::DataTpl::SDinv
Matrix6x SDinv
Used in computeMinverse.
Definition: data.hpp:174
pinocchio::DataTpl::dq_after
TangentVectorType dq_after
Generalized velocity after impact.
Definition: data.hpp:363
pinocchio::DataTpl::Matrix6x
Eigen::Matrix< Scalar, 6, Eigen::Dynamic, Options > Matrix6x
The 6d jacobian type (temporary)
Definition: data.hpp:73
pinocchio::DataTpl::C
MatrixXs C
The Coriolis matrix (a square matrix of dim model.nv).
Definition: data.hpp:159
pinocchio::DataTpl::kinematic_hessians
Tensor3x kinematic_hessians
Tensor containing the kinematic Hessian of all the joints.
Definition: data.hpp:378
pinocchio::DataTpl::BodyRegressorType
Eigen::Matrix< Scalar, 6, 10, Options > BodyRegressorType
The type of the body regressor.
Definition: data.hpp:82
pinocchio::DataTpl::Matrix3x
Eigen::Matrix< Scalar, 3, Eigen::Dynamic, Options > Matrix3x
The 3d jacobian type (temporary)
Definition: data.hpp:75
pinocchio::DataTpl::Ig
Inertia Ig
Centroidal Composite Rigid Body Inertia.
Definition: data.hpp:242
pinocchio::DataTpl::staticRegressor
Matrix3x staticRegressor
Matrix related to static regressor.
Definition: data.hpp:369
pinocchio::DataTpl::nle
VectorXs nle
Vector of Non Linear Effects (dim model.nv). It corresponds to concatenation of the Coriolis,...
Definition: data.hpp:135
pinocchio::FrameTpl
A Plucker coordinate frame attached to a parent joint inside a kinematic tree.
Definition: frame.hpp:41
pinocchio::DataTpl::M6tmp
Matrix6 M6tmp
Temporary for derivative algorithms.
Definition: data.hpp:204
pinocchio::DataTpl::ddq
TangentVectorType ddq
The joint accelerations computed from ABA.
Definition: data.hpp:209
pinocchio::DataTpl::potential_energy
Scalar potential_energy
Potential energy of the model.
Definition: data.hpp:343
pinocchio::DataTpl::kinetic_energy
Scalar kinetic_energy
Kinetic energy of the model.
Definition: data.hpp:340
pinocchio::DataTpl::g
VectorXs g
Vector of generalized gravity (dim model.nv).
Definition: data.hpp:140
pinocchio::DataTpl::D
VectorXs D
Diagonal of the joint space intertia matrix obtained by a Cholesky Decomposition.
Definition: data.hpp:263
pinocchio::DataTpl::d2tau_dqdq
Tensor3x d2tau_dqdq
SO Partial derivative of the joint torque vector with respect to the joint configuration.
Definition: data.hpp:382
pinocchio::DataTpl::M
MatrixXs M
The joint space inertia matrix (a square matrix of dim model.nv).
Definition: data.hpp:153
pinocchio::DataTpl::ddq_dv
MatrixXs ddq_dv
Partial derivative of the joint acceleration vector with respect to the joint velocity.
Definition: data.hpp:318
pinocchio::DataTpl::TangentVectorType
VectorXs TangentVectorType
Dense vectorized version of a joint tangent vector (e.g. velocity, acceleration, etc)....
Definition: data.hpp:70
pinocchio::DataTpl::Itmp
Matrix6 Itmp
Temporary for derivative algorithms.
Definition: data.hpp:201
pinocchio::JointModelTpl
Definition: fwd.hpp:93
pinocchio::DataTpl::lastChild
std::vector< int > lastChild
Index of the last child (for CRBA)
Definition: data.hpp:248
pinocchio::ForceTpl< Scalar, Options >
pinocchio::DataTpl::Minv
RowMatrixXs Minv
The inverse of the joint space inertia matrix (a square matrix of dim model.nv).
Definition: data.hpp:156
pinocchio::DataTpl::end_idx_v_fromRow
std::vector< int > end_idx_v_fromRow
End index of the Joint motion subspace.
Definition: data.hpp:257
pinocchio::DataTpl::joints
JointDataVector joints
Vector of pinocchio::JointData associated to the pinocchio::JointModel stored in model,...
Definition: data.hpp:89
pinocchio::DataTpl::IS
Matrix6x IS
Used in computeMinverse.
Definition: data.hpp:180
pinocchio::DataTpl::sDUiJt
MatrixXs sDUiJt
Temporary corresponding to .
Definition: data.hpp:357
pinocchio::DataTpl::dFda
Matrix6x dFda
Variation of the forceset with respect to the joint acceleration.
Definition: data.hpp:171
pinocchio::DataTpl::dtau_dv
MatrixXs dtau_dv
Partial derivative of the joint torque vector with respect to the joint velocity.
Definition: data.hpp:312
pinocchio::DataTpl::dtau_dq
MatrixXs dtau_dq
Partial derivative of the joint torque vector with respect to the joint configuration.
Definition: data.hpp:309
pinocchio::DataTpl::JMinvJt
MatrixXs JMinvJt
Inverse of the operational-space inertia matrix.
Definition: data.hpp:348
pinocchio::DataTpl::psid
Matrix6x psid
psidot Derivative of Jacobian w.r.t to the parent body moving v(p(j)) x Sj
Definition: data.hpp:293
pinocchio::DataTpl::psidd
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:297
pinocchio::DataTpl::U
MatrixXs U
Joint space intertia matrix square root (upper trianglular part) computed with a Cholesky Decompositi...
Definition: data.hpp:260
pinocchio::DataTpl::Dinv
VectorXs Dinv
Diagonal inverse of the joint space intertia matrix obtained by a Cholesky Decomposition.
Definition: data.hpp:266
pinocchio::DataTpl::dFdq
Matrix6x dFdq
Variation of the forceset with respect to the joint configuration.
Definition: data.hpp:165
pinocchio::DataTpl::UDinv
Matrix6x UDinv
Used in computeMinverse.
Definition: data.hpp:177
pinocchio::DataTpl::impulse_c
VectorXs impulse_c
Lagrange Multipliers corresponding to the contact impulses in pinocchio::impulseDynamics.
Definition: data.hpp:366
pinocchio::DataTpl::d2tau_dvdv
Tensor3x d2tau_dvdv
SO Partial derivative of the joint torque vector with respect to the joint velocity.
Definition: data.hpp:386
pinocchio::DataTpl::mass
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:333
pinocchio::DataTpl::parents_fromRow
std::vector< int > parents_fromRow
First previous non-zero row in M (used in Cholesky Decomposition).
Definition: data.hpp:272
pinocchio::DataTpl::J
Matrix6x J
Jacobian of joint placements.
Definition: data.hpp:283
pinocchio::DataTpl::dFdv
Matrix6x dFdv
Variation of the forceset with respect to the joint velocity.
Definition: data.hpp:168
pinocchio::DataTpl::d2tau_dqdv
Tensor3x d2tau_dqdv
SO Cross-Partial derivative of the joint torque vector with respect to the joint configuration/veloci...
Definition: data.hpp:390
pinocchio::DataTpl::ConfigVectorType
VectorXs ConfigVectorType
Dense vectorized version of a joint configuration vector.
Definition: data.hpp:66
pinocchio::DataTpl::dHdq
Matrix6x dHdq
Variation of the spatial momenta with respect to the joint configuration.
Definition: data.hpp:162
pinocchio::InertiaTpl< Scalar, Options >
pinocchio::DataTpl::nvSubtree
std::vector< int > nvSubtree
Dimension of the subtree motion space (for CRBA)
Definition: data.hpp:251
pinocchio::DataTpl::start_idx_v_fromRow
std::vector< int > start_idx_v_fromRow
Starting index of the Joint motion subspace.
Definition: data.hpp:254
pinocchio::Tensor< Scalar, 3, Options >
pinocchio::DataTpl::dAdq
Matrix6x dAdq
Variation of the spatial acceleration set with respect to the joint configuration.
Definition: data.hpp:303
pinocchio::DataTpl::dVdq
Matrix6x dVdq
Variation of the spatial velocity set with respect to the joint configuration.
Definition: data.hpp:300
pinocchio::MotionTpl< Scalar, Options >
pinocchio::DataTpl::dhg
Force dhg
Centroidal momentum time derivative.
Definition: data.hpp:238
pinocchio::ModelTpl< Scalar, Options, JointCollectionTpl >
pinocchio::DataTpl::hg
Force hg
Centroidal momentum quantity.
Definition: data.hpp:232
pinocchio::DataTpl::ddq_dq
MatrixXs ddq_dq
Partial derivative of the joint acceleration vector with respect to the joint configuration.
Definition: data.hpp:315
pinocchio::DataTpl::llt_JMinvJt
Eigen::LLT< MatrixXs > llt_JMinvJt
Cholesky decompostion of .
Definition: data.hpp:351
pinocchio::serialization::Serializable
Definition: serializable.hpp:16
pinocchio
Main pinocchio namespace.
Definition: treeview.dox:11