src/multibody/data.hpp
Go to the documentation of this file.
1 //
2 // Copyright (c) 2015-2020 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 
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 
64  typedef VectorXs ConfigVectorType;
65 
68  typedef VectorXs TangentVectorType;
69 
71  typedef Eigen::Matrix<Scalar,6,Eigen::Dynamic,Options> Matrix6x;
73  typedef Eigen::Matrix<Scalar,3,Eigen::Dynamic,Options> Matrix3x;
74 
75  typedef Eigen::Matrix<Scalar,6,6,Options> Matrix6;
76  typedef Eigen::Matrix<Scalar,6,6,Eigen::RowMajor | Options> RowMatrix6;
77  typedef Eigen::Matrix<Scalar,Eigen::Dynamic,Eigen::Dynamic,Eigen::RowMajor | Options> RowMatrixXs;
78 
80  typedef Eigen::Matrix<Scalar,6,10,Options> BodyRegressorType;
81 
83  typedef Tensor<Scalar,3,Options> Tensor3x;
84 
87  JointDataVector joints;
88 
91 
94 
96  PINOCCHIO_ALIGNED_STD_VECTOR(Motion) a_gf;
97 
99  PINOCCHIO_ALIGNED_STD_VECTOR(Motion) oa_gf;
100 
103 
105  PINOCCHIO_ALIGNED_STD_VECTOR(Motion) ov;
106 
110 
114 
117 
120 
123 
126 
128  TangentVectorType tau;
129 
133  VectorXs nle;
134 
138  VectorXs g;
139 
142 
145  PINOCCHIO_ALIGNED_STD_VECTOR(Inertia) Ycrb;
146 
148  PINOCCHIO_ALIGNED_STD_VECTOR(Matrix6) dYcrb; // TODO: change with dense symmetric matrix6
149 
151  MatrixXs M;
152 
154  RowMatrixXs Minv;
155 
157  MatrixXs C;
158 
160  Matrix6x dHdq;
161 
163  Matrix6x dFdq;
164 
166  Matrix6x dFdv;
167 
169  Matrix6x dFda;
170 
172  Matrix6x SDinv;
173 
175  Matrix6x UDinv;
176 
178  Matrix6x IS;
179 
181  PINOCCHIO_ALIGNED_STD_VECTOR(Matrix6) vxI;
182 
184  PINOCCHIO_ALIGNED_STD_VECTOR(Matrix6) Ivx;
185 
187  PINOCCHIO_ALIGNED_STD_VECTOR(Inertia) oinertias;
188 
190  PINOCCHIO_ALIGNED_STD_VECTOR(Inertia) oYcrb;
191 
193  PINOCCHIO_ALIGNED_STD_VECTOR(Matrix6) doYcrb;
194 
196  Matrix6 Itmp;
197 
199  Matrix6 M6tmp;
200  RowMatrix6 M6tmpR;
201  RowMatrix6 M6tmpR2;
202 
204  TangentVectorType ddq;
205 
206  // ABA internal data
208  PINOCCHIO_ALIGNED_STD_VECTOR(Matrix6) Yaba; // TODO: change with dense symmetric matrix6
209 
211  TangentVectorType u; // Joint Inertia
212 
213  // CCRBA return quantities
216  Matrix6x Ag;
217 
218  // dCCRBA return quantities
221  Matrix6x dAg;
222 
227  Force hg;
228 
233  Force dhg;
234 
237  Inertia Ig;
238 
240  PINOCCHIO_ALIGNED_STD_VECTOR(Matrix6x) Fcrb;
241 
243  std::vector<int> lastChild;
244 
246  std::vector<int> nvSubtree;
247 
249  std::vector<int> start_idx_v_fromRow;
250 
252  std::vector<int> end_idx_v_fromRow;
253 
255  MatrixXs U;
256 
258  VectorXs D;
259 
261  VectorXs Dinv;
262 
264  VectorXs tmp;
265 
267  std::vector<int> parents_fromRow;
268 
271  std::vector< std::vector<int> > supports_fromRow;
272 
274  std::vector<int> nvSubtree_fromRow;
275 
278  Matrix6x J;
279 
281  Matrix6x dJ;
282 
284  Matrix6x dVdq;
285 
287  Matrix6x dAdq;
288 
290  Matrix6x dAdv;
291 
293  MatrixXs dtau_dq;
294 
296  MatrixXs dtau_dv;
297 
299  MatrixXs ddq_dq;
300 
302  MatrixXs ddq_dv;
303 
306 
309 
311  PINOCCHIO_ALIGNED_STD_VECTOR(Vector3) vcom;
312 
314  PINOCCHIO_ALIGNED_STD_VECTOR(Vector3) acom;
315 
317  std::vector<Scalar> mass;
318 
321  Matrix3x Jcom;
322 
325 
328 
329  // Temporary variables used in forward dynamics
330 
332  MatrixXs JMinvJt;
333 
335  Eigen::LLT<MatrixXs> llt_JMinvJt;
336 
338  VectorXs lambda_c;
339 
341  MatrixXs sDUiJt;
342 
344  VectorXs torque_residual;
345 
347  TangentVectorType dq_after;
348 
350  VectorXs impulse_c;
351 
353  Matrix3x staticRegressor;
354 
356  BodyRegressorType bodyRegressor;
357 
360 
363 
369  explicit DataTpl(const Model & model);
370 
374  DataTpl() {}
375 
376  private:
377  void computeLastChild(const Model & model);
378  void computeParents_fromRow(const Model & model);
379  void computeSupports_fromRow(const Model & model);
380 
381  };
382 
383 } // namespace pinocchio
384 
385 /* --- Details -------------------------------------------------------------- */
386 /* --- Details -------------------------------------------------------------- */
387 /* --- Details -------------------------------------------------------------- */
388 #include "pinocchio/multibody/data.hxx"
389 
390 #endif // ifndef __pinocchio_multibody_data_hpp__
391 
Matrix6x dJ
Derivative of the Jacobian with respect to the time.
JointCollectionTpl const Eigen::MatrixBase< ConfigVectorType > const Eigen::MatrixBase< TangentVectorType > & v
TangentVectorType tau
Vector of joint torques (dim model.nv).
std::vector< int > nvSubtree_fromRow
Subtree of the current row index (used in Cholesky Decomposition).
FrameTpl< Scalar, Options > Frame
Eigen::Matrix< Scalar, Eigen::Dynamic, 1, Options > VectorXs
JointDataTpl< Scalar, Options, JointCollectionTpl > JointData
VectorXs g
Vector of generalized gravity (dim model.nv).
Eigen::Matrix< Scalar, Eigen::Dynamic, Eigen::Dynamic, Eigen::RowMajor|Options > RowMatrixXs
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.
Matrix6x UDinv
Used in computeMinverse.
MatrixXs dtau_dv
Partial derivative of the joint torque vector with respect to the joint velocity. ...
MatrixXs jointTorqueRegressor
Matrix related to joint torque regressor.
Matrix6x dAdv
Variation of the spatial acceleration set with respect to the joint velocity.
VectorXs tmp
Temporary of size NV used in Cholesky Decomposition.
Tensor3x kinematic_hessians
Tensor containing the kinematic Hessian of all the joints.
A Plucker coordinate frame attached to a parent joint inside a kinematic tree.
Matrix6x dFda
Variation of the forceset with respect to the joint acceleration.
void computeLastChild(const Model &model)
JointDataVector joints
Vector of pinocchio::JointData associated to the pinocchio::JointModel stored in model, encapsulated in JointDataAccessor.
BodyRegressorType bodyRegressor
Body regressor.
std::vector< int > end_idx_v_fromRow
End index of the Joint motion subspace.
typedef PINOCCHIO_ALIGNED_STD_VECTOR(JointModel) JointModelVector
Eigen::Matrix< Scalar, 6, 6, Eigen::RowMajor|Options > RowMatrix6
MotionTpl< Scalar, Options > Motion
VectorXs torque_residual
Temporary corresponding to the residual torque .
Eigen::LLT< MatrixXs > llt_JMinvJt
Cholesky decompostion of .
MatrixXs dtau_dq
Partial derivative of the joint torque vector with respect to the joint configuration.
VectorXs D
Diagonal of the joint space intertia matrix obtained by a Cholesky Decomposition. ...
TangentVectorType u
Intermediate quantity corresponding to apparent torque [ABA].
ModelTpl< Scalar, Options, JointCollectionTpl > Model
RowMatrixXs Minv
The inverse of the joint space inertia matrix (a square matrix of dim model.nv).
Matrix6 Itmp
Temporary for derivative algorithms.
VectorXs nle
Vector of Non Linear Effects (dim model.nv). It corresponds to concatenation of the Coriolis...
ForceTpl< Scalar, Options > Force
Matrix6x IS
Used in computeMinverse.
MatrixXs ddq_dq
Partial derivative of the joint acceleration vector with respect to the joint configuration.
pinocchio::Index Index
std::vector< Index > IndexVector
MatrixXs JMinvJt
Inverse of the operational-space inertia matrix.
Matrix6x dFdq
Variation of the forceset with respect to the joint configuration.
Matrix3x Jcom
Jacobian of center of mass.
EIGEN_MAKE_ALIGNED_OPERATOR_NEW typedef _Scalar Scalar
Matrix6x dAdq
Variation of the spatial acceleration set with respect to the joint configuration.
MatrixXs M
The joint space inertia matrix (a square matrix of dim model.nv).
MatrixXs C
The Coriolis matrix (a square matrix of dim model.nv).
JointCollectionTpl< Scalar, Options > JointCollection
Eigen::Matrix< Scalar, Eigen::Dynamic, Eigen::Dynamic, Options > MatrixXs
Matrix6x dAg
Centroidal Momentum Matrix Time Variation.
InertiaTpl< Scalar, Options > Inertia
TangentVectorType ddq
The joint accelerations computed from ABA.
std::vector< int > lastChild
Index of the last child (for CRBA)
JointModelTpl< Scalar, Options, JointCollectionTpl > JointModel
Matrix6x dFdv
Variation of the forceset with respect to the joint velocity.
Force dhg
Centroidal momentum time derivative.
pinocchio::JointIndex JointIndex
MatrixXs ddq_dv
Partial derivative of the joint acceleration vector with respect to the joint velocity.
Scalar kinetic_energy
Kinetic energy of the model.
VectorXs lambda_c
Lagrange Multipliers corresponding to the contact forces in pinocchio::forwardDynamics.
Main pinocchio namespace.
Definition: timings.cpp:30
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.
pinocchio::FrameIndex FrameIndex
Matrix6x dHdq
Variation of the spatial momenta with respect to the joint configuration.
VectorXs ConfigVectorType
Dense vectorized version of a joint configuration vector.
Matrix6x Ag
Centroidal Momentum Matrix.
TangentVectorType dq_after
Generalized velocity after impact.
Eigen::Matrix< Scalar, 3, Eigen::Dynamic, Options > Matrix3x
The 3d jacobian type (temporary)
Matrix6x SDinv
Used in computeMinverse.
Eigen::Matrix< Scalar, 6, 6, Options > Matrix6
MatrixXs sDUiJt
Temporary corresponding to .
std::size_t Index
Inertia Ig
Centroidal Composite Rigid Body Inertia.
h
Definition: ur5x4.py:45
void computeParents_fromRow(const Model &model)
Matrix3x staticRegressor
Matrix related to static regressor.
VectorXs impulse_c
Lagrange Multipliers corresponding to the contact impulses in pinocchio::impulseDynamics.
Scalar potential_energy
Potential energy of the model.
std::vector< int > nvSubtree
Dimension of the subtree motion space (for CRBA)
std::vector< int > parents_fromRow
First previous non-zero row in M (used in Cholesky Decomposition).
Force hg
Centroidal momentum quantity.
pinocchio::GeomIndex GeomIndex
Eigen::Matrix< Scalar, 6, Eigen::Dynamic, Options > Matrix6x
The 6d jacobian type (temporary)
MatrixXs U
Joint space intertia matrix square root (upper trianglular part) computed with a Cholesky Decompositi...
JointCollectionTpl & model
void computeSupports_fromRow(const Model &model)
Eigen::Matrix< Scalar, 6, 10, Options > BodyRegressorType
The type of the body regressor.
Eigen::Matrix< Scalar, 3, 1, Options > Vector3
SE3Tpl< Scalar, Options > SE3
Matrix6 M6tmp
Temporary for derivative algorithms.
std::vector< Scalar > mass
Vector of subtree mass. In other words, mass[j] is the mass of the subtree supported by joint ...
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).
Matrix6x dVdq
Variation of the spatial velocity set with respect to the joint configuration.


pinocchio
Author(s):
autogenerated on Tue Jun 1 2021 02:45:02