parallel/rnea.hpp
Go to the documentation of this file.
1 //
2 // Copyright (c) 2021 INRIA
3 //
4 
5 #ifndef __pinocchio_algorithm_parallel_rnea_hpp__
6 #define __pinocchio_algorithm_parallel_rnea_hpp__
7 
8 #include <omp.h>
9 
12 
13 namespace pinocchio
14 {
31  template<typename Scalar, int Options, template<typename,int> class JointCollectionTpl, typename ConfigVectorPool, typename TangentVectorPool1, typename TangentVectorPool2, typename TangentVectorPool3>
32  void rnea(const int num_threads,
34  const Eigen::MatrixBase<ConfigVectorPool> & q,
35  const Eigen::MatrixBase<TangentVectorPool1> & v,
36  const Eigen::MatrixBase<TangentVectorPool2> & a,
37  const Eigen::MatrixBase<TangentVectorPool3> & tau)
38  {
40  typedef typename Pool::Model Model;
41  typedef typename Pool::Data Data;
42  typedef typename Pool::DataVector DataVector;
43 
44  const Model & model = pool.model();
45  DataVector & datas = pool.datas();
46  TangentVectorPool3 & res = tau.const_cast_derived();
47 
48  PINOCCHIO_CHECK_INPUT_ARGUMENT(num_threads <= pool.size(), "The pool is too small");
53 
54  PINOCCHIO_CHECK_ARGUMENT_SIZE(q.cols(), v.cols());
55  PINOCCHIO_CHECK_ARGUMENT_SIZE(q.cols(), a.cols());
56  PINOCCHIO_CHECK_ARGUMENT_SIZE(q.cols(), res.cols());
57 
58  omp_set_num_threads(num_threads);
59  const Eigen::DenseIndex batch_size = res.cols();
60  Eigen::DenseIndex i = 0;
61 
62 #pragma omp parallel for
63  for(i = 0; i < batch_size; i++)
64  {
65  const int thread_id = omp_get_thread_num();
66  Data & data = datas[(size_t)thread_id];
67  res.col(i) = rnea(model,data,q.col(i),v.col(i),a.col(i));
68  }
69  }
70 }
71 
72 #endif // ifndef __pinocchio_algorithm_parallel_rnea_hpp__
PINOCCHIO_CHECK_ARGUMENT_SIZE
#define PINOCCHIO_CHECK_ARGUMENT_SIZE(...)
Macro to check if the size of an element is equal to the expected size.
Definition: include/pinocchio/macros.hpp:154
pinocchio::DataTpl
Definition: multibody/data.hpp:29
PINOCCHIO_CHECK_INPUT_ARGUMENT
#define PINOCCHIO_CHECK_INPUT_ARGUMENT(...)
Macro to check an assert-like condition and throw a std::invalid_argument exception (with a message) ...
Definition: include/pinocchio/macros.hpp:134
inverse-kinematics.i
int i
Definition: inverse-kinematics.py:20
run-algo-in-parallel.num_threads
num_threads
Definition: run-algo-in-parallel.py:10
setup.data
data
Definition: cmake/cython/setup.in.py:48
run-algo-in-parallel.batch_size
int batch_size
Definition: run-algo-in-parallel.py:11
rnea.hpp
forward-dynamics-derivatives.tau
tau
Definition: forward-dynamics-derivatives.py:23
res
res
pinocchio::rnea
void rnea(const int 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...
Definition: parallel/rnea.hpp:32
pinocchio::ModelPoolTpl
Definition: multibody/pool/model.hpp:19
run-algo-in-parallel.pool
pool
Definition: run-algo-in-parallel.py:8
model.hpp
pinocchio::q
JointCollectionTpl const Eigen::MatrixBase< ConfigVectorType > & q
Definition: joint-configuration.hpp:747
a
Vec3f a
pinocchio::v
JointCollectionTpl const Eigen::MatrixBase< ConfigVectorType > const Eigen::MatrixBase< TangentVectorType > & v
Definition: joint-configuration.hpp:748
pinocchio::Model
ModelTpl< double > Model
Definition: multibody/fwd.hpp:35
pinocchio::ModelTpl
Definition: multibody/fwd.hpp:23
pinocchio::model
JointCollectionTpl & model
Definition: joint-configuration.hpp:746
pinocchio
Main pinocchio namespace.
Definition: timings.cpp:28
pinocchio::Data
DataTpl< double > Data
Definition: multibody/fwd.hpp:36


pinocchio
Author(s):
autogenerated on Tue Feb 13 2024 03:43:59