centroidal.hpp
Go to the documentation of this file.
1 //
2 // Copyright (c) 2015-2019 CNRS INRIA
3 //
4 
5 #ifndef __pinocchio_algorithm_centroidal_hpp__
6 #define __pinocchio_algorithm_centroidal_hpp__
7 
11 
12 namespace pinocchio
13 {
14 
28  template<typename Scalar, int Options, template<typename,int> class JointCollectionTpl>
30  computeCentroidalMomentum(const ModelTpl<Scalar,Options,JointCollectionTpl> & model,
31  DataTpl<Scalar,Options,JointCollectionTpl> & data);
32 
50  template<typename Scalar, int Options, template<typename,int> class JointCollectionTpl,
51  typename ConfigVectorType, typename TangentVectorType>
55  const Eigen::MatrixBase<ConfigVectorType> & q,
56  const Eigen::MatrixBase<TangentVectorType> & v)
57  {
58  forwardKinematics(model,data,q.derived(),v.derived());
60  }
61 
66  template<typename Scalar, int Options, template<typename,int> class JointCollectionTpl,
67  typename ConfigVectorType, typename TangentVectorType>
68  PINOCCHIO_DEPRECATED
72  const Eigen::MatrixBase<ConfigVectorType> & q,
73  const Eigen::MatrixBase<TangentVectorType> & v)
74  {
76  }
77 
92  template<typename Scalar, int Options, template<typename,int> class JointCollectionTpl>
94  computeCentroidalMomentumTimeVariation(const ModelTpl<Scalar,Options,JointCollectionTpl> & model,
95  DataTpl<Scalar,Options,JointCollectionTpl> & data);
96 
117  template<typename Scalar, int Options, template<typename,int> class JointCollectionTpl,
118  typename ConfigVectorType, typename TangentVectorType1, typename TangentVectorType2>
122  const Eigen::MatrixBase<ConfigVectorType> & q,
123  const Eigen::MatrixBase<TangentVectorType1> & v,
124  const Eigen::MatrixBase<TangentVectorType2> & a)
125  {
128  }
129 
134  template<typename Scalar, int Options, template<typename,int> class JointCollectionTpl,
135  typename ConfigVectorType, typename TangentVectorType1, typename TangentVectorType2>
136  PINOCCHIO_DEPRECATED
140  const Eigen::MatrixBase<ConfigVectorType> & q,
141  const Eigen::MatrixBase<TangentVectorType1> & v,
142  const Eigen::MatrixBase<TangentVectorType2> & a)
143  {
145  }
146 
164  template<typename Scalar, int Options, template<typename,int> class JointCollectionTpl, typename ConfigVectorType, typename TangentVectorType>
166  ccrba(const ModelTpl<Scalar,Options,JointCollectionTpl> & model,
167  DataTpl<Scalar,Options,JointCollectionTpl> & data,
168  const Eigen::MatrixBase<ConfigVectorType> & q,
169  const Eigen::MatrixBase<TangentVectorType> & v);
170 
185  template<typename Scalar, int Options, template<typename,int> class JointCollectionTpl, typename ConfigVectorType>
187  computeCentroidalMap(const ModelTpl<Scalar,Options,JointCollectionTpl> & model,
188  DataTpl<Scalar,Options,JointCollectionTpl> & data,
189  const Eigen::MatrixBase<ConfigVectorType> & q);
190 
209  template<typename Scalar, int Options, template<typename,int> class JointCollectionTpl, typename ConfigVectorType, typename TangentVectorType>
211  dccrba(const ModelTpl<Scalar,Options,JointCollectionTpl> & model,
212  DataTpl<Scalar,Options,JointCollectionTpl> & data,
213  const Eigen::MatrixBase<ConfigVectorType> & q,
214  const Eigen::MatrixBase<TangentVectorType> & v);
215 
232  template<typename Scalar, int Options, template<typename,int> class JointCollectionTpl, typename ConfigVectorType, typename TangentVectorType>
234  computeCentroidalMapTimeVariation(const ModelTpl<Scalar,Options,JointCollectionTpl> & model,
235  DataTpl<Scalar,Options,JointCollectionTpl> & data,
236  const Eigen::MatrixBase<ConfigVectorType> & q,
237  const Eigen::MatrixBase<TangentVectorType> & v);
238 
239 } // namespace pinocchio
240 
241 /* --- Details -------------------------------------------------------------------- */
242 #include "pinocchio/algorithm/centroidal.hxx"
243 
244 #endif // ifndef __pinocchio_algorithm_centroidal_hpp__
pinocchio::DataTpl
Definition: multibody/data.hpp:29
pinocchio::forwardKinematics
void forwardKinematics(const ModelTpl< Scalar, Options, JointCollectionTpl > &model, DataTpl< Scalar, Options, JointCollectionTpl > &data, const Eigen::MatrixBase< ConfigVectorType > &q)
Update the joint placements according to the current joint configuration.
pinocchio::dccrba
const DataTpl< Scalar, Options, JointCollectionTpl >::Matrix6x & dccrba(const ModelTpl< Scalar, Options, JointCollectionTpl > &model, DataTpl< Scalar, Options, JointCollectionTpl > &data, const Eigen::MatrixBase< ConfigVectorType > &q, const Eigen::MatrixBase< TangentVectorType > &v)
Computes the time derivative of the Centroidal Momentum Matrix according to the current configuration...
kinematics.hpp
model.hpp
setup.data
data
Definition: cmake/cython/setup.in.py:48
pinocchio::computeCentroidalMomentumTimeVariation
const DataTpl< Scalar, Options, JointCollectionTpl >::Force & computeCentroidalMomentumTimeVariation(const ModelTpl< Scalar, Options, JointCollectionTpl > &model, DataTpl< Scalar, Options, JointCollectionTpl > &data)
Computes the Centroidal momemtum and its time derivatives, a.k.a. the total momenta of the system and...
pinocchio::computeCentroidalMomentum
const DataTpl< Scalar, Options, JointCollectionTpl >::Force & computeCentroidalMomentum(const ModelTpl< Scalar, Options, JointCollectionTpl > &model, DataTpl< Scalar, Options, JointCollectionTpl > &data)
Computes the Centroidal momentum, a.k.a. the total momenta of the system expressed around the center ...
pinocchio::computeCentroidalMap
const DataTpl< Scalar, Options, JointCollectionTpl >::Matrix6x & computeCentroidalMap(const ModelTpl< Scalar, Options, JointCollectionTpl > &model, DataTpl< Scalar, Options, JointCollectionTpl > &data, const Eigen::MatrixBase< ConfigVectorType > &q)
Computes the Centroidal Momentum Matrix,.
pinocchio::ccrba
const DataTpl< Scalar, Options, JointCollectionTpl >::Matrix6x & ccrba(const ModelTpl< Scalar, Options, JointCollectionTpl > &model, DataTpl< Scalar, Options, JointCollectionTpl > &data, const Eigen::MatrixBase< ConfigVectorType > &q, const Eigen::MatrixBase< TangentVectorType > &v)
Computes the Centroidal Momentum Matrix, the Composite Ridig Body Inertia as well as the centroidal m...
pinocchio::DataTpl::Force
ForceTpl< Scalar, Options > Force
Definition: multibody/data.hpp:43
pinocchio::computeCentroidalDynamics
const PINOCCHIO_DEPRECATED DataTpl< Scalar, Options, JointCollectionTpl >::Force & computeCentroidalDynamics(const ModelTpl< Scalar, Options, JointCollectionTpl > &model, DataTpl< Scalar, Options, JointCollectionTpl > &data, const Eigen::MatrixBase< ConfigVectorType > &q, const Eigen::MatrixBase< TangentVectorType > &v)
Computes the Centroidal momentum, a.k.a. the total momenta of the system expressed around the center ...
Definition: centroidal.hpp:70
pinocchio::DataTpl::Matrix6x
Eigen::Matrix< Scalar, 6, Eigen::Dynamic, Options > Matrix6x
The 6d jacobian type (temporary)
Definition: multibody/data.hpp:73
data.hpp
pinocchio::q
JointCollectionTpl const Eigen::MatrixBase< ConfigVectorType > & q
Definition: joint-configuration.hpp:747
a
Vec3f a
pinocchio::v
JointCollectionTpl const Eigen::MatrixBase< ConfigVectorType > const Eigen::MatrixBase< TangentVectorType > & v
Definition: joint-configuration.hpp:748
pinocchio::ModelTpl< Scalar, Options, JointCollectionTpl >
pinocchio::computeCentroidalMapTimeVariation
const DataTpl< Scalar, Options, JointCollectionTpl >::Matrix6x & computeCentroidalMapTimeVariation(const ModelTpl< Scalar, Options, JointCollectionTpl > &model, DataTpl< Scalar, Options, JointCollectionTpl > &data, const Eigen::MatrixBase< ConfigVectorType > &q, const Eigen::MatrixBase< TangentVectorType > &v)
Computes the Centroidal Momentum Matrix time derivative.
pinocchio::model
JointCollectionTpl & model
Definition: joint-configuration.hpp:746
pinocchio
Main pinocchio namespace.
Definition: timings.cpp:28


pinocchio
Author(s):
autogenerated on Tue Feb 13 2024 03:43:57