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> class JointCollectionTpl,
39  typename ConfigVectorType,
40  typename ReturnMatrixType>
42  const ModelTpl<Scalar, Options, JointCollectionTpl> & model,
43  DataTpl<Scalar, Options, JointCollectionTpl> & data,
44  const Eigen::MatrixBase<ConfigVectorType> & q,
45  const Eigen::MatrixBase<ReturnMatrixType> & gravity_partial_dq);
46 
68  template<
69  typename Scalar,
70  int Options,
71  template<typename, int> class JointCollectionTpl,
72  typename ConfigVectorType,
73  typename ReturnMatrixType>
75  const ModelTpl<Scalar, Options, JointCollectionTpl> & model,
76  DataTpl<Scalar, Options, JointCollectionTpl> & data,
77  const Eigen::MatrixBase<ConfigVectorType> & q,
78  const container::aligned_vector<ForceTpl<Scalar, Options>> & fext,
79  const Eigen::MatrixBase<ReturnMatrixType> & static_torque_partial_dq);
80 
110  template<
111  typename Scalar,
112  int Options,
113  template<typename, int> class JointCollectionTpl,
114  typename ConfigVectorType,
115  typename TangentVectorType1,
116  typename TangentVectorType2,
117  typename MatrixType1,
118  typename MatrixType2,
119  typename MatrixType3>
121  const ModelTpl<Scalar, Options, JointCollectionTpl> & model,
122  DataTpl<Scalar, Options, JointCollectionTpl> & data,
123  const Eigen::MatrixBase<ConfigVectorType> & q,
124  const Eigen::MatrixBase<TangentVectorType1> & v,
125  const Eigen::MatrixBase<TangentVectorType2> & a,
126  const Eigen::MatrixBase<MatrixType1> & rnea_partial_dq,
127  const Eigen::MatrixBase<MatrixType2> & rnea_partial_dv,
128  const Eigen::MatrixBase<MatrixType3> & rnea_partial_da);
129 
161  template<
162  typename Scalar,
163  int Options,
164  template<typename, int> class JointCollectionTpl,
165  typename ConfigVectorType,
166  typename TangentVectorType1,
167  typename TangentVectorType2,
168  typename MatrixType1,
169  typename MatrixType2,
170  typename MatrixType3>
172  const ModelTpl<Scalar, Options, JointCollectionTpl> & model,
173  DataTpl<Scalar, Options, JointCollectionTpl> & data,
174  const Eigen::MatrixBase<ConfigVectorType> & q,
175  const Eigen::MatrixBase<TangentVectorType1> & v,
176  const Eigen::MatrixBase<TangentVectorType2> & a,
177  const container::aligned_vector<ForceTpl<Scalar, Options>> & fext,
178  const Eigen::MatrixBase<MatrixType1> & rnea_partial_dq,
179  const Eigen::MatrixBase<MatrixType2> & rnea_partial_dv,
180  const Eigen::MatrixBase<MatrixType3> & rnea_partial_da);
181 
205  template<
206  typename Scalar,
207  int Options,
208  template<typename, int> class JointCollectionTpl,
209  typename ConfigVectorType,
210  typename TangentVectorType1,
211  typename TangentVectorType2>
213  const ModelTpl<Scalar, Options, JointCollectionTpl> & model,
214  DataTpl<Scalar, Options, JointCollectionTpl> & data,
215  const Eigen::MatrixBase<ConfigVectorType> & q,
216  const Eigen::MatrixBase<TangentVectorType1> & v,
217  const Eigen::MatrixBase<TangentVectorType2> & a);
218 
244  template<
245  typename Scalar,
246  int Options,
247  template<typename, int> class JointCollectionTpl,
248  typename ConfigVectorType,
249  typename TangentVectorType1,
250  typename TangentVectorType2>
252  const ModelTpl<Scalar, Options, JointCollectionTpl> & model,
253  DataTpl<Scalar, Options, JointCollectionTpl> & data,
254  const Eigen::MatrixBase<ConfigVectorType> & q,
255  const Eigen::MatrixBase<TangentVectorType1> & v,
256  const Eigen::MatrixBase<TangentVectorType2> & a,
257  const container::aligned_vector<ForceTpl<Scalar, Options>> & fext);
258 
259 } // namespace pinocchio
260 
261 #include "pinocchio/algorithm/rnea-derivatives.hxx"
262 
263 #if PINOCCHIO_ENABLE_TEMPLATE_INSTANTIATION
264  #include "pinocchio/algorithm/rnea-derivatives.txx"
265 #endif // PINOCCHIO_ENABLE_TEMPLATE_INSTANTIATION
266 
267 #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:1082
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:1083
a
Vec3f a
pinocchio::v
JointCollectionTpl const Eigen::MatrixBase< ConfigVectorType > const Eigen::MatrixBase< TangentVectorType > & v
Definition: joint-configuration.hpp:1084
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:1082
pinocchio
Main pinocchio namespace.
Definition: timings.cpp:27


pinocchio
Author(s):
autogenerated on Fri Nov 1 2024 02:41:48