algorithm/parallel/aba.hpp
Go to the documentation of this file.
1 //
2 // Copyright (c) 2022 INRIA
3 //
4 
5 #ifndef __pinocchio_algorithm_parallel_aba_hpp__
6 #define __pinocchio_algorithm_parallel_aba_hpp__
7 
11 
12 namespace pinocchio
13 {
32  template<
33  typename Scalar,
34  int Options,
35  template<typename, int>
36  class JointCollectionTpl,
37  typename ConfigVectorPool,
38  typename TangentVectorPool1,
39  typename TangentVectorPool2,
40  typename TangentVectorPool3>
42  const size_t num_threads,
44  const Eigen::MatrixBase<ConfigVectorPool> & q,
45  const Eigen::MatrixBase<TangentVectorPool1> & v,
46  const Eigen::MatrixBase<TangentVectorPool2> & tau,
47  const Eigen::MatrixBase<TangentVectorPool3> & a)
48  {
50  typedef typename Pool::Model Model;
51  typedef typename Pool::Data Data;
52  typedef typename Pool::ModelVector ModelVector;
53  typedef typename Pool::DataVector DataVector;
54 
55  PINOCCHIO_CHECK_INPUT_ARGUMENT(pool.size() > 0, "The pool should have at least one element");
56  PINOCCHIO_CHECK_INPUT_ARGUMENT(num_threads <= pool.size(), "The pool is too small");
57 
58  const ModelVector & models = pool.getModels();
59  const Model & model_check = models[0];
60  DataVector & datas = pool.getDatas();
61  TangentVectorPool3 & res = a.const_cast_derived();
62 
63  PINOCCHIO_CHECK_ARGUMENT_SIZE(q.rows(), model_check.nq);
64  PINOCCHIO_CHECK_ARGUMENT_SIZE(v.rows(), model_check.nv);
65  PINOCCHIO_CHECK_ARGUMENT_SIZE(a.rows(), model_check.nv);
66  PINOCCHIO_CHECK_ARGUMENT_SIZE(res.rows(), model_check.nv);
67 
68  PINOCCHIO_CHECK_ARGUMENT_SIZE(q.cols(), v.cols());
69  PINOCCHIO_CHECK_ARGUMENT_SIZE(q.cols(), a.cols());
70  PINOCCHIO_CHECK_ARGUMENT_SIZE(q.cols(), res.cols());
71 
73  const Eigen::DenseIndex batch_size = res.cols();
74  Eigen::DenseIndex i = 0;
75 
76 #pragma omp parallel for schedule( \
77  static) // we use static here as this is the same computationnal cost for all threads
78  for (i = 0; i < batch_size; i++)
79  {
80  const int thread_id = omp_get_thread_num();
81  const Model & model = models[(size_t)thread_id];
82  Data & data = datas[(size_t)thread_id];
83  res.col(i) = aba(model, data, q.col(i), v.col(i), tau.col(i), Convention::WORLD);
84  }
85  }
86 } // namespace pinocchio
87 
88 #endif // ifndef __pinocchio_algorithm_parallel_aba_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:217
pinocchio::DataTpl
Definition: context/generic.hpp:25
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:193
pinocchio::Options
Options
Definition: joint-configuration.hpp:1116
omp.hpp
pinocchio::Convention::WORLD
@ WORLD
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
pinocchio::python::Scalar
context::Scalar Scalar
Definition: admm-solver.cpp:29
pinocchio::res
ReturnType res
Definition: spatial/classic-acceleration.hpp:57
pinocchio::aba
const DataTpl< Scalar, Options, JointCollectionTpl >::TangentVectorType & aba(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 > &tau, const Convention convention=Convention::LOCAL)
The Articulated-Body algorithm. It computes the forward dynamics, aka the joint accelerations given t...
run-algo-in-parallel.batch_size
int batch_size
Definition: run-algo-in-parallel.py:11
pinocchio::python::context::Model
ModelTpl< Scalar, Options > Model
Definition: bindings/python/context/generic.hpp:61
pinocchio::abaInParallel
void abaInParallel(const size_t num_threads, ModelPoolTpl< Scalar, Options, JointCollectionTpl > &pool, const Eigen::MatrixBase< ConfigVectorPool > &q, const Eigen::MatrixBase< TangentVectorPool1 > &v, const Eigen::MatrixBase< TangentVectorPool2 > &tau, const Eigen::MatrixBase< TangentVectorPool3 > &a)
A parallel version of the Articulated Body algorithm. It computes the forward dynamics,...
Definition: algorithm/parallel/aba.hpp:41
aba.hpp
forward-dynamics-derivatives.tau
tau
Definition: forward-dynamics-derivatives.py:23
pinocchio::python::context::Data
DataTpl< Scalar, Options > Data
Definition: bindings/python/context/generic.hpp:62
pinocchio::Data
DataTpl< context::Scalar, context::Options > Data
Definition: multibody/fwd.hpp:34
pinocchio::ModelPoolTpl
Definition: multibody/pool/fwd.hpp:17
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:1117
a
Vec3f a
pinocchio::v
JointCollectionTpl const Eigen::MatrixBase< ConfigVectorType > const Eigen::MatrixBase< TangentVectorType > & v
Definition: joint-configuration.hpp:1118
pinocchio::ModelTpl::nv
int nv
Dimension of the velocity vector space.
Definition: multibody/model.hpp:102
pinocchio::set_default_omp_options
void set_default_omp_options(const size_t num_threads=(size_t) omp_get_max_threads())
Definition: omp.hpp:12
pinocchio::ModelTpl
Definition: context/generic.hpp:20
pinocchio::ModelTpl::nq
int nq
Dimension of the configuration vector representation.
Definition: multibody/model.hpp:99
pinocchio::Model
ModelTpl< context::Scalar, context::Options > Model
Definition: multibody/fwd.hpp:33
pinocchio::model
JointCollectionTpl & model
Definition: joint-configuration.hpp:1116
pinocchio
Main pinocchio namespace.
Definition: timings.cpp:27


pinocchio
Author(s):
autogenerated on Sat Jun 22 2024 02:41:42