rnea-derivatives.hpp
Go to the documentation of this file.
1 //
2 // Copyright (c) 2017-2019 CNRS INRIA
3 //
4 
5 #ifndef __pinocchio_algorithm_rnea_derivatives_hpp__
6 #define __pinocchio_algorithm_rnea_derivatives_hpp__
7 
10 
12 
13 namespace pinocchio
14 {
15 
35  template<
36  typename Scalar,
37  int Options,
38  template<typename, int>
39  class JointCollectionTpl,
40  typename ConfigVectorType,
41  typename ReturnMatrixType>
43  const ModelTpl<Scalar, Options, JointCollectionTpl> & model,
44  DataTpl<Scalar, Options, JointCollectionTpl> & data,
45  const Eigen::MatrixBase<ConfigVectorType> & q,
46  const Eigen::MatrixBase<ReturnMatrixType> & gravity_partial_dq);
47 
69  template<
70  typename Scalar,
71  int Options,
72  template<typename, int>
73  class JointCollectionTpl,
74  typename ConfigVectorType,
75  typename ReturnMatrixType>
77  const ModelTpl<Scalar, Options, JointCollectionTpl> & model,
78  DataTpl<Scalar, Options, JointCollectionTpl> & data,
79  const Eigen::MatrixBase<ConfigVectorType> & q,
80  const container::aligned_vector<ForceTpl<Scalar, Options>> & fext,
81  const Eigen::MatrixBase<ReturnMatrixType> & static_torque_partial_dq);
82 
112  template<
113  typename Scalar,
114  int Options,
115  template<typename, int>
116  class JointCollectionTpl,
117  typename ConfigVectorType,
118  typename TangentVectorType1,
119  typename TangentVectorType2,
120  typename MatrixType1,
121  typename MatrixType2,
122  typename MatrixType3>
124  const ModelTpl<Scalar, Options, JointCollectionTpl> & model,
125  DataTpl<Scalar, Options, JointCollectionTpl> & data,
126  const Eigen::MatrixBase<ConfigVectorType> & q,
127  const Eigen::MatrixBase<TangentVectorType1> & v,
128  const Eigen::MatrixBase<TangentVectorType2> & a,
129  const Eigen::MatrixBase<MatrixType1> & rnea_partial_dq,
130  const Eigen::MatrixBase<MatrixType2> & rnea_partial_dv,
131  const Eigen::MatrixBase<MatrixType3> & rnea_partial_da);
132 
164  template<
165  typename Scalar,
166  int Options,
167  template<typename, int>
168  class JointCollectionTpl,
169  typename ConfigVectorType,
170  typename TangentVectorType1,
171  typename TangentVectorType2,
172  typename MatrixType1,
173  typename MatrixType2,
174  typename MatrixType3>
176  const ModelTpl<Scalar, Options, JointCollectionTpl> & model,
177  DataTpl<Scalar, Options, JointCollectionTpl> & data,
178  const Eigen::MatrixBase<ConfigVectorType> & q,
179  const Eigen::MatrixBase<TangentVectorType1> & v,
180  const Eigen::MatrixBase<TangentVectorType2> & a,
181  const container::aligned_vector<ForceTpl<Scalar, Options>> & fext,
182  const Eigen::MatrixBase<MatrixType1> & rnea_partial_dq,
183  const Eigen::MatrixBase<MatrixType2> & rnea_partial_dv,
184  const Eigen::MatrixBase<MatrixType3> & rnea_partial_da);
185 
209  template<
210  typename Scalar,
211  int Options,
212  template<typename, int>
213  class JointCollectionTpl,
214  typename ConfigVectorType,
215  typename TangentVectorType1,
216  typename TangentVectorType2>
218  const ModelTpl<Scalar, Options, JointCollectionTpl> & model,
219  DataTpl<Scalar, Options, JointCollectionTpl> & data,
220  const Eigen::MatrixBase<ConfigVectorType> & q,
221  const Eigen::MatrixBase<TangentVectorType1> & v,
222  const Eigen::MatrixBase<TangentVectorType2> & a);
223 
249  template<
250  typename Scalar,
251  int Options,
252  template<typename, int>
253  class JointCollectionTpl,
254  typename ConfigVectorType,
255  typename TangentVectorType1,
256  typename TangentVectorType2>
258  const ModelTpl<Scalar, Options, JointCollectionTpl> & model,
259  DataTpl<Scalar, Options, JointCollectionTpl> & data,
260  const Eigen::MatrixBase<ConfigVectorType> & q,
261  const Eigen::MatrixBase<TangentVectorType1> & v,
262  const Eigen::MatrixBase<TangentVectorType2> & a,
263  const container::aligned_vector<ForceTpl<Scalar, Options>> & fext);
264 
265 } // namespace pinocchio
266 
267 #include "pinocchio/algorithm/rnea-derivatives.hxx"
268 
269 #if PINOCCHIO_ENABLE_TEMPLATE_INSTANTIATION
270  #include "pinocchio/algorithm/rnea-derivatives.txx"
271 #endif // PINOCCHIO_ENABLE_TEMPLATE_INSTANTIATION
272 
273 #endif // ifndef __pinocchio_algorithm_rnea_derivatives_hpp__
pinocchio::computeRNEADerivatives
void computeRNEADerivatives(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, const Eigen::MatrixBase< MatrixType1 > &rnea_partial_dq, const Eigen::MatrixBase< MatrixType2 > &rnea_partial_dv, const Eigen::MatrixBase< MatrixType3 > &rnea_partial_da)
Computes the partial derivatives of the Recursive Newton Euler Algorithms with respect to the joint c...
aligned-vector.hpp
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::computeStaticTorqueDerivatives
void computeStaticTorqueDerivatives(const ModelTpl< Scalar, Options, JointCollectionTpl > &model, DataTpl< Scalar, Options, JointCollectionTpl > &data, const Eigen::MatrixBase< ConfigVectorType > &q, const container::aligned_vector< ForceTpl< Scalar, Options >> &fext, const Eigen::MatrixBase< ReturnMatrixType > &static_torque_partial_dq)
Computes the partial derivative of the generalized gravity and external forces contributions (a....
pinocchio::computeGeneralizedGravityDerivatives
void computeGeneralizedGravityDerivatives(const ModelTpl< Scalar, Options, JointCollectionTpl > &model, DataTpl< Scalar, Options, JointCollectionTpl > &data, const Eigen::MatrixBase< ConfigVectorType > &q, const Eigen::MatrixBase< ReturnMatrixType > &gravity_partial_dq)
Computes the partial derivative of the generalized gravity contribution with respect to the joint con...
data.hpp
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::model
JointCollectionTpl & model
Definition: joint-configuration.hpp:1116
pinocchio
Main pinocchio namespace.
Definition: timings.cpp:27


pinocchio
Author(s):
autogenerated on Tue Jun 25 2024 02:42:40