multibody/data.hpp
Go to the documentation of this file.
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 
11 
20 
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 
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 
85 
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>
100 
102  typedef Eigen::Matrix<Scalar, 6, 10, Options> BodyRegressorType;
103 
106 
107  // TODO Remove when API is stabilized
112 
115  JointDataVector joints;
116 
119 
122 
126 
129  PINOCCHIO_ALIGNED_STD_VECTOR(Motion) oa_augmented;
130 
133 
137 
140 
143 
148 
153 
158  PINOCCHIO_ALIGNED_STD_VECTOR(Force) of_augmented;
159 
162 
165 
168 
171 
174 
180 
185 
188 
193 
196  PINOCCHIO_ALIGNED_STD_VECTOR(Matrix6) dYcrb; // TODO: change with dense symmetric matrix6
197 
200 
203 
206 
209 
212 
215 
218 
221 
224 
227 
230 
233 
237 
240 
243 
246 
249 
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 
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 
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 
330 
333 
337 
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 
388 
391 
395 
399 
403 
410 
413 
420 
423 
429 
435 
441 
444  std::vector<Scalar> mass;
445 
451 
454 
457 
460 
461  // Temporary variables used in forward dynamics
462 
465 
468 
472 
476 
479 
482 
485 
488 
492 
495 
498 
501 
504 
507 
512  PINOCCHIO_ALIGNED_STD_VECTOR(int) par_cons_ind;
515  PINOCCHIO_ALIGNED_STD_VECTOR(int) constraint_ind;
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 
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__
pinocchio::DataTpl::d2tau_dvdv
Tensor3x d2tau_dvdv
SO Partial derivative of the joint torque vector with respect to the joint velocity.
Definition: multibody/data.hpp:552
pinocchio::DataTpl::JointModel
JointModelTpl< Scalar, Options, JointCollectionTpl > JointModel
Definition: multibody/data.hpp:68
pinocchio::InertiaTpl< Scalar, Options >
pinocchio::traits< DataTpl< _Scalar, _Options, JointCollectionTpl > >::Scalar
_Scalar Scalar
Definition: multibody/data.hpp:36
pinocchio::DataTpl::TangentVectorType
VectorXs TangentVectorType
Dense vectorized version of a joint tangent vector (e.g. velocity, acceleration, etc)....
Definition: multibody/data.hpp:89
pinocchio::DataTpl::M
MatrixXs M
The joint space inertia matrix (a square matrix of dim model.nv).
Definition: multibody/data.hpp:199
pinocchio::DataTpl::parents_fromRow
std::vector< int > parents_fromRow
First previous non-zero row in M (used in Cholesky Decomposition).
Definition: multibody/data.hpp:342
pinocchio::DataTpl::MatrixXs
Eigen::Matrix< Scalar, Eigen::Dynamic, Eigen::Dynamic, Options > MatrixXs
Definition: multibody/data.hpp:74
pinocchio::DataTpl::ddq_dv
RowMatrixXs ddq_dv
Partial derivative of the joint acceleration vector with respect to the joint velocity.
Definition: multibody/data.hpp:398
pinocchio::DataTpl::Scalar
EIGEN_MAKE_ALIGNED_OPERATOR_NEW typedef _Scalar Scalar
Definition: multibody/data.hpp:46
pinocchio::DataTpl::ddq
TangentVectorType ddq
The joint accelerations computed from ABA.
Definition: multibody/data.hpp:256
pinocchio::DataTpl::JMinvJt
MatrixXs JMinvJt
Inverse of the operational-space inertia matrix.
Definition: multibody/data.hpp:464
pinocchio::FrameIndex
Index FrameIndex
Definition: multibody/fwd.hpp:28
pinocchio::DataTpl::dFdq
Matrix6x dFdq
Variation of the forceset with respect to the joint configuration.
Definition: multibody/data.hpp:211
fwd.hpp
pinocchio::DataTpl::computeLastChild
void computeLastChild(const Model &model)
pinocchio::DataTpl::d2tau_dqdq
Tensor3x d2tau_dqdq
SO Partial derivative of the joint torque vector with respect to the joint configuration.
Definition: multibody/data.hpp:548
pinocchio::DataTpl::GeomIndex
pinocchio::GeomIndex GeomIndex
Definition: multibody/data.hpp:64
pinocchio::DataTpl::g
VectorXs g
Vector of generalized gravity (dim model.nv).
Definition: multibody/data.hpp:184
pinocchio::NumericalBase
Definition: fwd.hpp:89
Eigen
pinocchio::DataTpl::kineticEnergyRegressor
RowVectorXs kineticEnergyRegressor
Matrix related to kinetic energy regressor.
Definition: multibody/data.hpp:503
pinocchio::DataTpl::osim_llt
Eigen::LLT< MatrixXs > osim_llt
Definition: multibody/data.hpp:516
pinocchio::DataTpl::PINOCCHIO_ALIGNED_STD_VECTOR
typedef PINOCCHIO_ALIGNED_STD_VECTOR(JointModel) JointModelVector
pinocchio::DataTpl::M6tmpR2
RowMatrix6 M6tmpR2
Definition: multibody/data.hpp:253
pinocchio::DataTpl::UDinv
Matrix6x UDinv
Used in computeMinverse.
Definition: multibody/data.hpp:223
pinocchio::DataTpl
Definition: context/generic.hpp:25
pinocchio::DataTpl::M6tmp
Matrix6 M6tmp
Temporary for derivative algorithms.
Definition: multibody/data.hpp:251
contact-cholesky.hpp
pinocchio::DataTpl::dAdv
Matrix6x dAdv
Variation of the spatial acceleration set with respect to the joint velocity.
Definition: multibody/data.hpp:383
pinocchio::DataTpl::dAg
Matrix6x dAg
Centroidal Momentum Matrix Time Variation.
Definition: multibody/data.hpp:290
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: multibody/data.hpp:444
pinocchio::DataTpl::dvc_dq
MatrixXs dvc_dq
Stack of partial derivative of the contact frame acceleration with respect to the joint parameters.
Definition: multibody/data.hpp:406
pinocchio::DataTpl::dhg
Force dhg
Centroidal momentum time derivative.
Definition: multibody/data.hpp:305
pinocchio::DataTpl::JointIndex
pinocchio::JointIndex JointIndex
Definition: multibody/data.hpp:63
pinocchio::DataTpl::RowMatrixXs
Eigen::Matrix< Scalar, Eigen::Dynamic, Eigen::Dynamic, Eigen::RowMajor|Options > RowMatrixXs
Definition: multibody/data.hpp:99
pinocchio::DataTpl::dlambda_dv
MatrixXs dlambda_dv
Definition: multibody/data.hpp:417
pinocchio::DataTpl::dJ
Matrix6x dJ
Derivative of the Jacobian with respect to the time.
Definition: multibody/data.hpp:363
pinocchio::DataTpl::lambda_c_prox
VectorXs lambda_c_prox
Proximal Lagrange Multipliers used in the computation of the Forward Dynamics computations.
Definition: multibody/data.hpp:475
B
B
aligned-vector.hpp
pinocchio::DataTpl::ConfigVectorType
VectorXs ConfigVectorType
Dense vectorized version of a joint configuration vector.
Definition: multibody/data.hpp:84
pinocchio::DataTpl::d2tau_dqdv
Tensor3x d2tau_dqdv
SO Cross-Partial derivative of the joint torque vector with respect to the joint configuration/veloci...
Definition: multibody/data.hpp:556
pinocchio::DataTpl::kinetic_energy
Scalar kinetic_energy
Kinetic energy of the system.
Definition: multibody/data.hpp:453
pinocchio::DataTpl::ContactCholeskyDecomposition
PINOCCHIO_COMPILER_DIAGNOSTIC_PUSH PINOCCHIO_COMPILER_DIAGNOSTIC_IGNORED_DEPRECECATED_DECLARATIONS typedef ContactCholeskyDecompositionTpl< Scalar, Options > ContactCholeskyDecomposition
Definition: multibody/data.hpp:110
pinocchio::SE3Tpl< Scalar, Options >
pinocchio::DataTpl::jointTorqueRegressor
MatrixXs jointTorqueRegressor
Matrix related to joint torque regressor.
Definition: multibody/data.hpp:500
pinocchio::DataTpl::RowMatrix6
Eigen::Matrix< Scalar, 6, 6, Eigen::RowMajor|Options > RowMatrix6
Definition: multibody/data.hpp:97
pinocchio::DataTpl::dFdv
Matrix6x dFdv
Variation of the forceset with respect to the joint velocity.
Definition: multibody/data.hpp:214
pinocchio::DataTpl::kinematic_hessians
Tensor3x kinematic_hessians
Tensor containing the kinematic Hessian of all the joints.
Definition: multibody/data.hpp:525
serializable.hpp
inertia.hpp
pinocchio::DataTpl::FrameIndex
pinocchio::FrameIndex FrameIndex
Definition: multibody/data.hpp:65
PINOCCHIO_COMPILER_DIAGNOSTIC_POP
#define PINOCCHIO_COMPILER_DIAGNOSTIC_POP
Definition: include/pinocchio/macros.hpp:130
pinocchio::DataTpl::lambda_c
VectorXs lambda_c
Lagrange Multipliers corresponding to the contact forces in pinocchio::forwardDynamics.
Definition: multibody/data.hpp:471
pinocchio::JointDataTpl
Definition: multibody/joint/fwd.hpp:162
pinocchio::DataTpl::u
TangentVectorType u
Intermediate quantity corresponding to apparent torque [ABA].
Definition: multibody/data.hpp:279
pinocchio::DataTpl::dac_da
MatrixXs dac_da
Definition: multibody/data.hpp:409
pinocchio::DataTpl::nvSubtree
std::vector< int > nvSubtree
Dimension of the subtree motion space (for CRBA)
Definition: multibody/data.hpp:319
motion.hpp
pinocchio::DataTpl::dFda
Matrix6x dFda
Variation of the forceset with respect to the joint acceleration.
Definition: multibody/data.hpp:217
pinocchio::DataTpl::ddJ
Matrix6x ddJ
Second derivative of the Jacobian with respect to the time.
Definition: multibody/data.hpp:366
autodiff-rnea.f
f
Definition: autodiff-rnea.py:24
pinocchio::DataTpl::joints
PINOCCHIO_COMPILER_DIAGNOSTIC_POP JointDataVector joints
Vector of pinocchio::JointData associated to the pinocchio::JointModel stored in model,...
Definition: multibody/data.hpp:115
pinocchio::DataTpl::SDinv
Matrix6x SDinv
Used in computeMinverse.
Definition: multibody/data.hpp:220
pinocchio::DataTpl::end_idx_v_fromRow
std::vector< int > end_idx_v_fromRow
End index of the Joint motion subspace.
Definition: multibody/data.hpp:325
pinocchio::DataTpl::Itmp
Matrix6 Itmp
Temporary for derivative algorithms.
Definition: multibody/data.hpp:248
pinocchio::DataTpl::sDUiJt
MatrixXs sDUiJt
Temporary corresponding to .
Definition: multibody/data.hpp:481
pinocchio::DataTpl::Vector6c
Eigen::Matrix< Scalar, 6, 1, Options > Vector6c
Definition: multibody/data.hpp:80
pinocchio::DataTpl::Vector6
Eigen::Matrix< Scalar, 6, 1, Options > Vector6
Definition: multibody/data.hpp:78
pinocchio::FrameTpl
A Plucker coordinate frame attached to a parent joint inside a kinematic tree.
Definition: multibody/frame.hpp:55
pinocchio::DataTpl::potential_energy
Scalar potential_energy
Potential energy of the system.
Definition: multibody/data.hpp:456
pinocchio::Index
PINOCCHIO_COMPILER_DIAGNOSTIC_POP typedef std::size_t Index
Definition: multibody/fwd.hpp:22
pinocchio::DataTpl::extended_motion_propagator
extended_motion_propagator
Definition: multibody/data.hpp:569
pinocchio::DataTpl::ddq_dtau
RowMatrixXs ddq_dtau
Partial derivative of the joint acceleration vector with respect to the joint torques.
Definition: multibody/data.hpp:402
pinocchio::DataTpl::staticRegressor
Matrix3x staticRegressor
Matrix related to static regressor.
Definition: multibody/data.hpp:494
pinocchio::DataTpl::C
MatrixXs C
The Coriolis matrix (a square matrix of dim model.nv).
Definition: multibody/data.hpp:205
pinocchio::DataTpl::Inertia
InertiaTpl< Scalar, Options > Inertia
Definition: multibody/data.hpp:59
pinocchio::DataTpl::VectorXs
Eigen::Matrix< Scalar, Eigen::Dynamic, 1, Options > VectorXs
Definition: multibody/data.hpp:75
pinocchio::DataTpl::Tensor3x
Tensor< Scalar, 3, Options > Tensor3x
&#160;
Definition: multibody/data.hpp:105
pinocchio::DataTpl::JointData
JointDataTpl< Scalar, Options, JointCollectionTpl > JointData
Definition: multibody/data.hpp:69
pinocchio::DataTpl::oYaba_contact
oYaba_contact
Articulated Body Inertia matrix with contact apparent inertia, of a given the subtree and expressed i...
Definition: multibody/data.hpp:270
pinocchio::DataTpl::Matrix3x
Eigen::Matrix< Scalar, 3, Eigen::Dynamic, Options > Matrix3x
The 3d jacobian type (temporary)
Definition: multibody/data.hpp:94
pinocchio::DataTpl::dtau_dq
RowMatrixXs dtau_dq
Partial derivative of the joint torque vector with respect to the joint configuration.
Definition: multibody/data.hpp:387
pinocchio::DataTpl::computeSupports_fromRow
void computeSupports_fromRow(const Model &model)
pinocchio::DataTpl::d2tau_dadq
Tensor3x d2tau_dadq
SO Cross-Partial derivative of the joint torque vector with respect to the joint acceleration/configu...
Definition: multibody/data.hpp:562
pinocchio::DataTpl::Vector3
Eigen::Matrix< Scalar, 3, 1, Options > Vector3
Definition: multibody/data.hpp:77
pinocchio::DataTpl::nvSubtree_fromRow
std::vector< int > nvSubtree_fromRow
Subtree of the current row index (used in Cholesky Decomposition).
Definition: multibody/data.hpp:351
pinocchio::DataTpl::Index
pinocchio::Index Index
Definition: multibody/data.hpp:62
joint-generic.hpp
se3.hpp
pinocchio::DataTpl::tau
TangentVectorType tau
Vector of joint torques (dim model.nv).
Definition: multibody/data.hpp:173
pinocchio::JointModelTpl
Definition: multibody/joint/fwd.hpp:155
pinocchio::DataTpl::Minv
RowMatrixXs Minv
The inverse of the joint space inertia matrix (a square matrix of dim model.nv).
Definition: multibody/data.hpp:202
pinocchio::DataTpl::dlambda_dq
MatrixXs dlambda_dq
Partial derivatives of the constraints forces with respect to the joint configuration,...
Definition: multibody/data.hpp:416
pinocchio::DataTpl::diff_lambda_c
VectorXs diff_lambda_c
Difference between two consecutive iterations of the proxy algorithm.
Definition: multibody/data.hpp:478
pinocchio::ForceTpl< Scalar, Options >
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: multibody/data.hpp:374
pinocchio::DataTpl::Jcom
Matrix3x Jcom
Jacobian of center of mass.
Definition: multibody/data.hpp:450
PINOCCHIO_COMPILER_DIAGNOSTIC_IGNORED_DEPRECECATED_DECLARATIONS
#define PINOCCHIO_COMPILER_DIAGNOSTIC_IGNORED_DEPRECECATED_DECLARATIONS
Definition: include/pinocchio/macros.hpp:131
set
void set(bool ownStorage, Vec3f *points_, unsigned int num_points_)
pinocchio::DataTpl::primal_rhs_contact
VectorXs primal_rhs_contact
Primal RHS in contact dynamic equations.
Definition: multibody/data.hpp:538
pinocchio::DataTpl::Options
@ Options
Definition: multibody/data.hpp:49
PINOCCHIO_COMPILER_DIAGNOSTIC_PUSH
#define PINOCCHIO_COMPILER_DIAGNOSTIC_PUSH
macros for pragma push/pop/ignore deprecated warnings
Definition: include/pinocchio/macros.hpp:129
pinocchio::DataTpl::IndexVector
std::vector< Index > IndexVector
Definition: multibody/data.hpp:66
pinocchio::DataTpl::psid
Matrix6x psid
psidot Derivative of Jacobian w.r.t to the parent body moving v(p(j)) x Sj
Definition: multibody/data.hpp:370
pinocchio::DataTpl::Ag
Matrix6x Ag
Centroidal Momentum Matrix.
Definition: multibody/data.hpp:284
pinocchio::DataTpl::tmp
VectorXs tmp
Temporary of size NV used in Cholesky Decomposition.
Definition: multibody/data.hpp:339
pinocchio::DataTpl::Vector6r
Eigen::Matrix< Scalar, 1, 6, Eigen::RowMajor|Options > Vector6r
Definition: multibody/data.hpp:81
ur5x4.h
h
Definition: ur5x4.py:50
pinocchio::DataTpl::lastChild
std::vector< int > lastChild
Index of the last child (for CRBA)
Definition: multibody/data.hpp:316
pinocchio::DataTpl::start_idx_v_fromRow
std::vector< int > start_idx_v_fromRow
Starting index of the Joint motion subspace.
Definition: multibody/data.hpp:322
pinocchio::DataTpl::Dinv
VectorXs Dinv
Diagonal inverse of the joint space intertia matrix obtained by a Cholesky Decomposition.
Definition: multibody/data.hpp:336
a
Vec3f a
pinocchio::DataTpl::dac_dv
MatrixXs dac_dv
Definition: multibody/data.hpp:408
pinocchio::DataTpl::bodyRegressor
BodyRegressorType bodyRegressor
Body regressor.
Definition: multibody/data.hpp:497
pinocchio::v
JointCollectionTpl const Eigen::MatrixBase< ConfigVectorType > const Eigen::MatrixBase< TangentVectorType > & v
Definition: joint-configuration.hpp:1084
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: multibody/data.hpp:348
pinocchio::DataTpl::J
Matrix6x J
Jacobian of joint placements.
Definition: multibody/data.hpp:360
pinocchio::DataTpl::mechanical_energy
Scalar mechanical_energy
Mechanical energy of the system.
Definition: multibody/data.hpp:459
pinocchio::DataTpl::dq_after
TangentVectorType dq_after
Generalized velocity after impact.
Definition: multibody/data.hpp:487
pinocchio::DataTpl::Motion
MotionTpl< Scalar, Options > Motion
Definition: multibody/data.hpp:57
pinocchio::DataTpl::BodyRegressorType
Eigen::Matrix< Scalar, 6, 10, Options > BodyRegressorType
The type of the body regressor.
Definition: multibody/data.hpp:102
pinocchio::DataTpl::ddq_dq
RowMatrixXs ddq_dq
Partial derivative of the joint acceleration vector with respect to the joint configuration.
Definition: multibody/data.hpp:394
pinocchio::DataTpl::M6tmpR
RowMatrix6 M6tmpR
Definition: multibody/data.hpp:252
std
Definition: autodiff/casadi/utils/static-if.hpp:64
pinocchio::DataTpl::llt_JMinvJt
Eigen::LLT< MatrixXs > llt_JMinvJt
Cholesky decompostion of .
Definition: multibody/data.hpp:467
pinocchio::DataTpl::hg
Force hg
Centroidal momentum quantity.
Definition: multibody/data.hpp:297
pinocchio::DataTpl::dHdq
Matrix6x dHdq
Variation of the spatial momenta set with respect to the joint configuration.
Definition: multibody/data.hpp:208
pinocchio::DataTpl::U
MatrixXs U
Joint space intertia matrix square root (upper trianglular part) computed with a Cholesky Decompositi...
Definition: multibody/data.hpp:329
pinocchio::DataTpl::D
VectorXs D
Diagonal of the joint space intertia matrix obtained by a Cholesky Decomposition.
Definition: multibody/data.hpp:332
pinocchio::DataTpl::torque_residual
VectorXs torque_residual
Temporary corresponding to the residual torque .
Definition: multibody/data.hpp:484
pinocchio::DataTpl::potentialEnergyRegressor
RowVectorXs potentialEnergyRegressor
Matrix related to potential energy regressor.
Definition: multibody/data.hpp:506
pinocchio::DataTpl::Matrix6
Eigen::Matrix< Scalar, 6, 6, Options > Matrix6
Definition: multibody/data.hpp:96
pinocchio::DataTpl::Force
ForceTpl< Scalar, Options > Force
Definition: multibody/data.hpp:58
pinocchio::JointIndex
Index JointIndex
Definition: multibody/fwd.hpp:26
pinocchio::DataTpl::Matrix6x
Eigen::Matrix< Scalar, 6, Eigen::Dynamic, Options > Matrix6x
The 6d jacobian type (temporary)
Definition: multibody/data.hpp:92
pinocchio::DataTpl::dlambda_dtau
MatrixXs dlambda_dtau
Definition: multibody/data.hpp:418
pinocchio::DataTpl::Model
ModelTpl< Scalar, Options, JointCollectionTpl > Model
Definition: multibody/data.hpp:54
pinocchio::traits
Common traits structure to fully define base classes for CRTP.
Definition: fwd.hpp:71
pinocchio::DataTpl::dac_dq
MatrixXs dac_dq
Definition: multibody/data.hpp:407
pinocchio::DataTpl::IS
Matrix6x IS
Used in computeMinverse.
Definition: multibody/data.hpp:226
pinocchio::Tensor< Scalar, 3, Options >
pinocchio::DataTpl::computeParents_fromRow
void computeParents_fromRow(const Model &model)
pinocchio::ContactCholeskyDecompositionTpl
Definition: algorithm/fwd.hpp:17
pinocchio::DataTpl::dtau_dv
RowMatrixXs dtau_dv
Partial derivative of the joint torque vector with respect to the joint velocity.
Definition: multibody/data.hpp:390
pinocchio::DataTpl::dlambda_dx_prox
MatrixXs dlambda_dx_prox
Definition: multibody/data.hpp:419
pinocchio::DataTpl::RowVectorXs
Eigen::Matrix< Scalar, 1, Eigen::Dynamic, Options|Eigen::RowMajor > RowVectorXs
Definition: multibody/data.hpp:76
pinocchio::MotionTpl< Scalar, Options >
pinocchio::ModelTpl
Definition: context/generic.hpp:20
tensor.hpp
pinocchio::DataTpl::SE3
SE3Tpl< Scalar, Options > SE3
Definition: multibody/data.hpp:56
force.hpp
pinocchio::DataTpl::dVdq
Matrix6x dVdq
Variation of the spatial velocity set with respect to the joint configuration.
Definition: multibody/data.hpp:377
pinocchio::DataTpl::osim
MatrixXs osim
Operational space inertia matrix;.
Definition: multibody/data.hpp:412
pinocchio::DataTpl::primal_dual_contact_solution
VectorXs primal_dual_contact_solution
RHS vector when solving the contact dynamics KKT problem.
Definition: multibody/data.hpp:535
pinocchio::DataTpl::Ig
Inertia Ig
Centroidal Composite Rigid Body Inertia.
Definition: multibody/data.hpp:310
pinocchio::GeomIndex
Index GeomIndex
Definition: multibody/fwd.hpp:27
fwd.hpp
pinocchio::DataTpl::JointCollection
JointCollectionTpl< Scalar, Options > JointCollection
Definition: multibody/data.hpp:52
robot-wrapper-viewer.com
com
Definition: robot-wrapper-viewer.py:45
pinocchio::serialization::Serializable
Definition: serialization/serializable.hpp:16
pinocchio::DataTpl::Frame
FrameTpl< Scalar, Options > Frame
Definition: multibody/data.hpp:60
pinocchio::DataTpl::impulse_c
VectorXs impulse_c
Lagrange Multipliers corresponding to the contact impulses in pinocchio::impulseDynamics.
Definition: multibody/data.hpp:491
pinocchio::model
JointCollectionTpl & model
Definition: joint-configuration.hpp:1082
pinocchio::DataTpl::contact_chol
ContactCholeskyDecomposition contact_chol
Cholesky decomposition of the KKT contact matrix.
Definition: multibody/data.hpp:532
pinocchio
Main pinocchio namespace.
Definition: timings.cpp:27
pinocchio::DataTpl::nle
VectorXs nle
Vector of Non Linear Effects (dim model.nv). It corresponds to concatenation of the Coriolis,...
Definition: multibody/data.hpp:179
pinocchio::DataTpl::drhs_prox
MatrixXs drhs_prox
Definition: multibody/data.hpp:419
pinocchio::DataTpl::dAdq
Matrix6x dAdq
Variation of the spatial acceleration set with respect to the joint configuration.
Definition: multibody/data.hpp:380


pinocchio
Author(s):
autogenerated on Sun Dec 22 2024 03:41:08