rnea.hpp
Go to the documentation of this file.
1 //
2 // Copyright (c) 2015-2020 CNRS INRIA
3 //
4 
5 #ifndef __pinocchio_algorithm_rnea_hpp__
6 #define __pinocchio_algorithm_rnea_hpp__
7 
10 
11 namespace pinocchio
12 {
30  template<
31  typename Scalar,
32  int Options,
33  template<typename, int>
34  class JointCollectionTpl,
35  typename ConfigVectorType,
36  typename TangentVectorType1,
37  typename TangentVectorType2>
39  const ModelTpl<Scalar, Options, JointCollectionTpl> & model,
40  DataTpl<Scalar, Options, JointCollectionTpl> & data,
41  const Eigen::MatrixBase<ConfigVectorType> & q,
42  const Eigen::MatrixBase<TangentVectorType1> & v,
43  const Eigen::MatrixBase<TangentVectorType2> & a);
44 
66  template<
67  typename Scalar,
68  int Options,
69  template<typename, int>
70  class JointCollectionTpl,
71  typename ConfigVectorType,
72  typename TangentVectorType1,
73  typename TangentVectorType2,
74  typename ForceDerived>
76  const ModelTpl<Scalar, Options, JointCollectionTpl> & model,
77  DataTpl<Scalar, Options, JointCollectionTpl> & data,
78  const Eigen::MatrixBase<ConfigVectorType> & q,
79  const Eigen::MatrixBase<TangentVectorType1> & v,
80  const Eigen::MatrixBase<TangentVectorType2> & a,
81  const container::aligned_vector<ForceDerived> & fext);
82 
101  template<
102  typename Scalar,
103  int Options,
104  template<typename, int>
105  class JointCollectionTpl,
106  typename ConfigVectorType,
107  typename TangentVectorType>
109  const ModelTpl<Scalar, Options, JointCollectionTpl> & model,
110  DataTpl<Scalar, Options, JointCollectionTpl> & data,
111  const Eigen::MatrixBase<ConfigVectorType> & q,
112  const Eigen::MatrixBase<TangentVectorType> & v);
113 
130  template<
131  typename Scalar,
132  int Options,
133  template<typename, int>
134  class JointCollectionTpl,
135  typename ConfigVectorType>
138  const ModelTpl<Scalar, Options, JointCollectionTpl> & model,
139  DataTpl<Scalar, Options, JointCollectionTpl> & data,
140  const Eigen::MatrixBase<ConfigVectorType> & q);
141 
161  template<
162  typename Scalar,
163  int Options,
164  template<typename, int>
165  class JointCollectionTpl,
166  typename ConfigVectorType>
169  const ModelTpl<Scalar, Options, JointCollectionTpl> & model,
170  DataTpl<Scalar, Options, JointCollectionTpl> & data,
171  const Eigen::MatrixBase<ConfigVectorType> & q,
172  const container::aligned_vector<ForceTpl<Scalar, Options>> & fext);
173 
192  template<
193  typename Scalar,
194  int Options,
195  template<typename, int>
196  class JointCollectionTpl,
197  typename ConfigVectorType,
198  typename TangentVectorType>
200  const ModelTpl<Scalar, Options, JointCollectionTpl> & model,
201  DataTpl<Scalar, Options, JointCollectionTpl> & data,
202  const Eigen::MatrixBase<ConfigVectorType> & q,
203  const Eigen::MatrixBase<TangentVectorType> & v);
204 
219  template<typename Scalar, int Options, template<typename, int> class JointCollectionTpl>
221  const ModelTpl<Scalar, Options, JointCollectionTpl> & model,
222  DataTpl<Scalar, Options, JointCollectionTpl> & data);
223 
224 } // namespace pinocchio
225 
226 /* --- Details -------------------------------------------------------------------- */
227 #include "pinocchio/algorithm/rnea.hxx"
228 
229 #if PINOCCHIO_ENABLE_TEMPLATE_INSTANTIATION
230  #include "pinocchio/algorithm/rnea.txx"
231 #endif // PINOCCHIO_ENABLE_TEMPLATE_INSTANTIATION
232 
233 #endif // ifndef __pinocchio_algorithm_rnea_hpp__
pinocchio::DataTpl::TangentVectorType
VectorXs TangentVectorType
Dense vectorized version of a joint tangent vector (e.g. velocity, acceleration, etc)....
Definition: multibody/data.hpp:88
pinocchio::DataTpl::MatrixXs
Eigen::Matrix< Scalar, Eigen::Dynamic, Eigen::Dynamic, Options > MatrixXs
Definition: multibody/data.hpp:74
pinocchio::Options
Options
Definition: joint-configuration.hpp:1116
model.hpp
setup.data
data
Definition: cmake/cython/setup.in.py:48
pinocchio::python::Scalar
context::Scalar Scalar
Definition: admm-solver.cpp:29
pinocchio::getCoriolisMatrix
const DataTpl< Scalar, Options, JointCollectionTpl >::MatrixXs & getCoriolisMatrix(const ModelTpl< Scalar, Options, JointCollectionTpl > &model, DataTpl< Scalar, Options, JointCollectionTpl > &data)
Retrives the Coriolis Matrix of the Lagrangian dynamics:
pinocchio::computeStaticTorque
const DataTpl< Scalar, Options, JointCollectionTpl >::TangentVectorType & computeStaticTorque(const ModelTpl< Scalar, Options, JointCollectionTpl > &model, DataTpl< Scalar, Options, JointCollectionTpl > &data, const Eigen::MatrixBase< ConfigVectorType > &q, const container::aligned_vector< ForceTpl< Scalar, Options >> &fext)
Computes the generalized static torque contribution of the Lagrangian dynamics:
data.hpp
pinocchio::nonLinearEffects
const DataTpl< Scalar, Options, JointCollectionTpl >::TangentVectorType & nonLinearEffects(const ModelTpl< Scalar, Options, JointCollectionTpl > &model, DataTpl< Scalar, Options, JointCollectionTpl > &data, const Eigen::MatrixBase< ConfigVectorType > &q, const Eigen::MatrixBase< TangentVectorType > &v)
Computes the non-linear effects (Corriolis, centrifual and gravitationnal effects),...
pinocchio::q
JointCollectionTpl const Eigen::MatrixBase< ConfigVectorType > & q
Definition: joint-configuration.hpp:1117
a
Vec3f a
pinocchio::v
JointCollectionTpl const Eigen::MatrixBase< ConfigVectorType > const Eigen::MatrixBase< TangentVectorType > & v
Definition: joint-configuration.hpp:1118
pinocchio::container::aligned_vector
std::vector< T, Eigen::aligned_allocator< T > > aligned_vector
Definition: container/aligned-vector.hpp:21
pinocchio::rnea
const DataTpl< Scalar, Options, JointCollectionTpl >::TangentVectorType & rnea(const ModelTpl< Scalar, Options, JointCollectionTpl > &model, DataTpl< Scalar, Options, JointCollectionTpl > &data, const Eigen::MatrixBase< ConfigVectorType > &q, const Eigen::MatrixBase< TangentVectorType1 > &v, const Eigen::MatrixBase< TangentVectorType2 > &a)
The Recursive Newton-Euler algorithm. It computes the inverse dynamics, aka the joint torques accordi...
pinocchio::computeCoriolisMatrix
const DataTpl< Scalar, Options, JointCollectionTpl >::MatrixXs & computeCoriolisMatrix(const ModelTpl< Scalar, Options, JointCollectionTpl > &model, DataTpl< Scalar, Options, JointCollectionTpl > &data, const Eigen::MatrixBase< ConfigVectorType > &q, const Eigen::MatrixBase< TangentVectorType > &v)
Computes the Coriolis Matrix of the Lagrangian dynamics:
pinocchio::model
JointCollectionTpl & model
Definition: joint-configuration.hpp:1116
pinocchio
Main pinocchio namespace.
Definition: timings.cpp:27
pinocchio::computeGeneralizedGravity
const DataTpl< Scalar, Options, JointCollectionTpl >::TangentVectorType & computeGeneralizedGravity(const ModelTpl< Scalar, Options, JointCollectionTpl > &model, DataTpl< Scalar, Options, JointCollectionTpl > &data, const Eigen::MatrixBase< ConfigVectorType > &q)
Computes the generalized gravity contribution of the Lagrangian dynamics:


pinocchio
Author(s):
autogenerated on Sat Jun 1 2024 02:40:38