Go to the documentation of this file.
5 #ifndef __pinocchio_algorithm_parallel_rnea_hpp__
6 #define __pinocchio_algorithm_parallel_rnea_hpp__
34 template<
typename,
int>
class JointCollectionTpl,
35 typename ConfigVectorPool,
36 typename TangentVectorPool1,
37 typename TangentVectorPool2,
38 typename TangentVectorPool3>
42 const Eigen::MatrixBase<ConfigVectorPool> &
q,
43 const Eigen::MatrixBase<TangentVectorPool1> &
v,
44 const Eigen::MatrixBase<TangentVectorPool2> &
a,
45 const Eigen::MatrixBase<TangentVectorPool3> &
tau)
50 typedef typename Pool::ModelVector ModelVector;
51 typedef typename Pool::DataVector DataVector;
56 const ModelVector & models =
pool.getModels();
57 const Model & model_check = models[0];
58 DataVector & datas =
pool.getDatas();
59 TangentVectorPool3 &
res =
tau.const_cast_derived();
72 Eigen::DenseIndex
i = 0;
74 #pragma omp parallel for schedule( \
75 static) // we use static here as this is the same computationnal cost for all threads
78 const int thread_id = omp_get_thread_num();
79 const Model &
model = models[(size_t)thread_id];
80 Data &
data = datas[(size_t)thread_id];
86 #endif // ifndef __pinocchio_algorithm_parallel_rnea_hpp__
#define PINOCCHIO_CHECK_ARGUMENT_SIZE(...)
Macro to check if the size of an element is equal to the expected size.
#define PINOCCHIO_CHECK_INPUT_ARGUMENT(...)
Macro to check an assert-like condition and throw a std::invalid_argument exception (with a message) ...
ModelTpl< Scalar, Options > Model
DataTpl< Scalar, Options > Data
DataTpl< context::Scalar, context::Options > Data
void rneaInParallel(const size_t num_threads, ModelPoolTpl< Scalar, Options, JointCollectionTpl > &pool, const Eigen::MatrixBase< ConfigVectorPool > &q, const Eigen::MatrixBase< TangentVectorPool1 > &v, const Eigen::MatrixBase< TangentVectorPool2 > &a, const Eigen::MatrixBase< TangentVectorPool3 > &tau)
The Recursive Newton-Euler algorithm. It computes the inverse dynamics, aka the joint torques accordi...
JointCollectionTpl const Eigen::MatrixBase< ConfigVectorType > & q
JointCollectionTpl const Eigen::MatrixBase< ConfigVectorType > const Eigen::MatrixBase< TangentVectorType > & v
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...
int nv
Dimension of the velocity vector space.
void set_default_omp_options(const size_t num_threads=(size_t) omp_get_max_threads())
int nq
Dimension of the configuration vector representation.
ModelTpl< context::Scalar, context::Options > Model
JointCollectionTpl & model
Main pinocchio namespace.
pinocchio
Author(s):
autogenerated on Fri Nov 1 2024 02:41:48