bindings/python/algorithm/parallel/rnea.cpp
Go to the documentation of this file.
1 //
2 // Copyright (c) 2021 INRIA
3 //
4 
6 #include "pinocchio/algorithm/parallel/rnea.hpp"
7 
9 
10 namespace pinocchio
11 {
12  namespace python
13  {
14 
15  static void rnea_proxy_res(const int num_thread, ModelPool & pool,
16  const Eigen::MatrixXd & q, const Eigen::MatrixXd & v, const Eigen::MatrixXd & a,
17  Eigen::Ref<Eigen::MatrixXd> tau)
18  {
19  rnea(num_thread,pool,q,v,a,tau);
20  }
21 
22  static Eigen::MatrixXd rnea_proxy(const int num_thread, ModelPool & pool,
23  const Eigen::MatrixXd & q, const Eigen::MatrixXd & v, const Eigen::MatrixXd & a)
24  {
25  Eigen::MatrixXd tau(v.rows(),v.cols());
26  rnea(num_thread,pool,q,v,a,tau);
27  return tau;
28  }
29 
31  {
32  namespace bp = boost::python;
33 
34  using namespace Eigen;
35 
36  bp::def("rnea",
37  rnea_proxy,
38  bp::args("num_thread","pool","q","v","a"),
39  "Computes in parallel the RNEA and returns the result.\n\n"
40  "Parameters:\n"
41  "\tnum_thread: number of threads used for the computation\n"
42  "\tpool: pool of model/data\n"
43  "\tq: the joint configuration vector (size model.nq x batch_size)\n"
44  "\tv: the joint velocity vector (size model.nv x batch_size)\n"
45  "\ta: the joint acceleration vector (size model.nv x batch_size)\n");
46 
47  bp::def("rnea",
49  bp::args("num_thread","pool","q","v","a","tau"),
50  "Computes in parallel the RNEA and stores the result in tau.\n\n"
51  "Parameters:\n"
52  "\tnum_thread: number of threads used for the computation\n"
53  "\tpool: pool of model/data\n"
54  "\tq: the joint configuration vector (size model.nq x batch_size)\n"
55  "\tv: the joint velocity vector (size model.nv x batch_size)\n"
56  "\ta: the joint acceleration vector (size model.nv x batch_size)\n"
57  "\ttau: the resulting joint torque vectors (size model.nv x batch_size)\n");
58 
59  }
60 
61  } // namespace python
62 } // namespace pinocchio
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...
static Eigen::MatrixXd rnea_proxy(const int num_thread, ModelPool &pool, const Eigen::MatrixXd &q, const Eigen::MatrixXd &v, const Eigen::MatrixXd &a)
JointCollectionTpl const Eigen::MatrixBase< ConfigVectorType > & q
static void rnea_proxy_res(const int num_thread, ModelPool &pool, const Eigen::MatrixXd &q, const Eigen::MatrixXd &v, const Eigen::MatrixXd &a, Eigen::Ref< Eigen::MatrixXd > tau)
Main pinocchio namespace.
Definition: timings.cpp:30


pinocchio
Author(s):
autogenerated on Tue Jun 1 2021 02:45:04