pinocchio  3.7.0
A fast and flexible implementation of Rigid Body Dynamics algorithms and their analytical derivatives
 
Loading...
Searching...
No Matches
rnea.hpp
1//
2// Copyright (c) 2021-2022 INRIA
3//
4
5#ifndef __pinocchio_algorithm_parallel_rnea_hpp__
6#define __pinocchio_algorithm_parallel_rnea_hpp__
7
8#include "pinocchio/multibody/pool/model.hpp"
9#include "pinocchio/algorithm/rnea.hpp"
10#include "pinocchio/algorithm/parallel/omp.hpp"
11
12namespace pinocchio
13{
31 template<
32 typename Scalar,
33 int Options,
34 template<typename, int> class JointCollectionTpl,
35 typename ConfigVectorPool,
36 typename TangentVectorPool1,
37 typename TangentVectorPool2,
38 typename TangentVectorPool3>
40 const size_t num_threads,
42 const Eigen::MatrixBase<ConfigVectorPool> & q,
43 const Eigen::MatrixBase<TangentVectorPool1> & v,
44 const Eigen::MatrixBase<TangentVectorPool2> & a,
45 const Eigen::MatrixBase<TangentVectorPool3> & tau)
46 {
48 typedef typename Pool::Model Model;
49 typedef typename Pool::Data Data;
50 typedef typename Pool::ModelVector ModelVector;
51 typedef typename Pool::DataVector DataVector;
52
53 PINOCCHIO_CHECK_INPUT_ARGUMENT(pool.size() > 0, "The pool should have at least one element");
54 PINOCCHIO_CHECK_INPUT_ARGUMENT(num_threads <= pool.size(), "The pool is too small");
55
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();
60
61 PINOCCHIO_CHECK_ARGUMENT_SIZE(q.rows(), model_check.nq);
62 PINOCCHIO_CHECK_ARGUMENT_SIZE(v.rows(), model_check.nv);
63 PINOCCHIO_CHECK_ARGUMENT_SIZE(a.rows(), model_check.nv);
64 PINOCCHIO_CHECK_ARGUMENT_SIZE(res.rows(), model_check.nv);
65
66 PINOCCHIO_CHECK_ARGUMENT_SIZE(q.cols(), v.cols());
67 PINOCCHIO_CHECK_ARGUMENT_SIZE(q.cols(), a.cols());
68 PINOCCHIO_CHECK_ARGUMENT_SIZE(q.cols(), res.cols());
69
70 set_default_omp_options(num_threads);
71 const Eigen::DenseIndex batch_size = res.cols();
72 Eigen::DenseIndex i = 0;
73
74#pragma omp parallel for schedule( \
75 static) // we use static here as this is the same computationnal cost for all threads
76 for (i = 0; i < batch_size; i++)
77 {
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];
81 res.col(i) = rnea(model, data, q.col(i), v.col(i), a.col(i));
82 }
83 }
84} // namespace pinocchio
85
86#endif // ifndef __pinocchio_algorithm_parallel_rnea_hpp__
Main pinocchio namespace.
Definition treeview.dox:11
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...
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...
Definition rnea.hpp:39