Go to the documentation of this file.
5 #ifndef __pinocchio_algorithm_rnea_hpp__
6 #define __pinocchio_algorithm_rnea_hpp__
33 template<
typename,
int>
class JointCollectionTpl,
34 typename ConfigVectorType,
35 typename TangentVectorType1,
36 typename TangentVectorType2>
38 const ModelTpl<Scalar, Options, JointCollectionTpl> &
model,
39 DataTpl<Scalar, Options, JointCollectionTpl> &
data,
40 const Eigen::MatrixBase<ConfigVectorType> &
q,
41 const Eigen::MatrixBase<TangentVectorType1> &
v,
42 const Eigen::MatrixBase<TangentVectorType2> &
a);
68 template<
typename,
int>
class JointCollectionTpl,
69 typename ConfigVectorType,
70 typename TangentVectorType1,
71 typename TangentVectorType2,
72 typename ForceDerived>
74 const ModelTpl<Scalar, Options, JointCollectionTpl> &
model,
75 DataTpl<Scalar, Options, JointCollectionTpl> &
data,
76 const Eigen::MatrixBase<ConfigVectorType> &
q,
77 const Eigen::MatrixBase<TangentVectorType1> &
v,
78 const Eigen::MatrixBase<TangentVectorType2> &
a,
79 const container::aligned_vector<ForceDerived> & fext);
102 template<
typename,
int>
class JointCollectionTpl,
103 typename ConfigVectorType,
104 typename TangentVectorType>
106 const ModelTpl<Scalar, Options, JointCollectionTpl> &
model,
107 DataTpl<Scalar, Options, JointCollectionTpl> &
data,
108 const Eigen::MatrixBase<ConfigVectorType> &
q,
109 const Eigen::MatrixBase<TangentVectorType> &
v);
130 template<
typename,
int>
class JointCollectionTpl,
131 typename ConfigVectorType>
134 const ModelTpl<Scalar, Options, JointCollectionTpl> &
model,
135 DataTpl<Scalar, Options, JointCollectionTpl> &
data,
136 const Eigen::MatrixBase<ConfigVectorType> &
q);
160 template<
typename,
int>
class JointCollectionTpl,
161 typename ConfigVectorType>
164 const ModelTpl<Scalar, Options, JointCollectionTpl> &
model,
165 DataTpl<Scalar, Options, JointCollectionTpl> &
data,
166 const Eigen::MatrixBase<ConfigVectorType> &
q,
190 template<
typename,
int>
class JointCollectionTpl,
191 typename ConfigVectorType,
192 typename TangentVectorType>
194 const ModelTpl<Scalar, Options, JointCollectionTpl> &
model,
195 DataTpl<Scalar, Options, JointCollectionTpl> &
data,
196 const Eigen::MatrixBase<ConfigVectorType> &
q,
197 const Eigen::MatrixBase<TangentVectorType> &
v);
213 template<
typename Scalar,
int Options,
template<
typename,
int>
class JointCollectionTpl>
215 const ModelTpl<Scalar, Options, JointCollectionTpl> &
model,
216 DataTpl<Scalar, Options, JointCollectionTpl> &
data);
221 #include "pinocchio/algorithm/rnea.hxx"
223 #if PINOCCHIO_ENABLE_TEMPLATE_INSTANTIATION
224 #include "pinocchio/algorithm/rnea.txx"
225 #endif // PINOCCHIO_ENABLE_TEMPLATE_INSTANTIATION
227 #endif // ifndef __pinocchio_algorithm_rnea_hpp__
VectorXs TangentVectorType
Dense vectorized version of a joint tangent vector (e.g. velocity, acceleration, etc)....
Eigen::Matrix< Scalar, Eigen::Dynamic, Eigen::Dynamic, Options > MatrixXs
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:
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:
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),...
JointCollectionTpl const Eigen::MatrixBase< ConfigVectorType > & q
JointCollectionTpl const Eigen::MatrixBase< ConfigVectorType > const Eigen::MatrixBase< TangentVectorType > & v
std::vector< T, Eigen::aligned_allocator< T > > aligned_vector
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...
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:
JointCollectionTpl & model
Main pinocchio namespace.
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 Fri Nov 1 2024 02:41:48