timings-parallel.cpp
Go to the documentation of this file.
1 //
2 // Copyright (c) 2021 INRIA
3 //
4 
5 #include "pinocchio/algorithm/parallel/rnea.hpp"
6 #include "pinocchio/algorithm/parallel/aba.hpp"
7 #include "pinocchio/algorithm/joint-configuration.hpp"
8 #include "pinocchio/parsers/sample-models.hpp"
9 
10 #ifdef PINOCCHIO_WITH_HPP_FCL
11  #include "pinocchio/algorithm/parallel/geometry.hpp"
12 #endif
13 
14 #include "pinocchio/parsers/urdf.hpp"
15 #include "pinocchio/parsers/srdf.hpp"
16 #include "pinocchio/parsers/sample-models.hpp"
17 
18 #include <iostream>
19 
20 #include "pinocchio/utils/timer.hpp"
21 
22 
23 int main(int /*argc*/, const char ** /*argv*/)
24 {
25  using namespace Eigen;
26  using namespace pinocchio;
27 
28  typedef Eigen::Matrix<bool,Eigen::Dynamic,1> VectorXb;
29 // typedef Eigen::Matrix<bool,Eigen::Dynamic,Eigen::Dynamic> MatrixXb;
30 
32  #ifdef NDEBUG
33  const int NBT = 4000;
34 
35  #else
36  const int NBT = 1;
37  std::cout << "(the time score in debug mode is not relevant) " << std::endl;
38  #endif
39 
40  const int BATCH_SIZE = 256;
41  const int NUM_THREADS = omp_get_max_threads();
42 
43  const std::string filename = PINOCCHIO_MODEL_DIR + std::string("/example-robot-data/robots/talos_data/robots/talos_reduced.urdf");
44 
47 
48  std::cout << "nq = " << model.nq << std::endl;
49  std::cout << "nv = " << model.nv << std::endl;
50  std::cout << "name = " << model.name << std::endl;
51 
52 #ifdef PINOCCHIO_WITH_HPP_FCL
53  const std::string package_path = PINOCCHIO_MODEL_DIR;
54  hpp::fcl::MeshLoaderPtr mesh_loader = make_shared<hpp::fcl::CachedMeshLoader>();
55  const std::string srdf_filename = PINOCCHIO_MODEL_DIR + std::string("/example-robot-data/robots/talos_data/srdf/talos.srdf");
56  std::vector<std::string> package_paths(1,package_path);
57  pinocchio::GeometryModel geometry_model;
58  pinocchio::urdf::buildGeom(model,filename,COLLISION,geometry_model,package_paths,mesh_loader);
59 
60  geometry_model.addAllCollisionPairs();
61  pinocchio::srdf::removeCollisionPairs(model,geometry_model,srdf_filename,false);
62 
63  GeometryData geometry_data(geometry_model);
64  {
65  int num_active_collision_pairs = 0;
66  for(size_t k = 0; k < geometry_data.activeCollisionPairs.size(); ++k)
67  {
68  if(geometry_data.activeCollisionPairs[k])
69  num_active_collision_pairs++;
70  }
71  std::cout << "active collision pairs = " << num_active_collision_pairs << std::endl;
72  }
73 #endif
74 
75  std::cout << "--" << std::endl;
76  std::cout << "NUM_THREADS: " << NUM_THREADS << std::endl;
77  std::cout << "BATCH_SIZE: " << BATCH_SIZE << std::endl;
78  std::cout << "--" << std::endl;
79 
80  pinocchio::Data data(model);
81  const VectorXd qmax = Eigen::VectorXd::Ones(model.nq);
82 
83  MatrixXd qs(model.nq,BATCH_SIZE);
84  MatrixXd vs(model.nv,BATCH_SIZE);
85  MatrixXd as(model.nv,BATCH_SIZE);
86  MatrixXd taus(model.nv,BATCH_SIZE);
87  MatrixXd res(model.nv,BATCH_SIZE);
88 
90  for(size_t i=0; i < NBT; ++i)
91  {
92  q_vec[i] = randomConfiguration(model,-qmax,qmax);
93  }
94 
95  for(Eigen::DenseIndex i=0; i < BATCH_SIZE; ++i)
96  {
97  qs.col(i) = randomConfiguration(model,-qmax,qmax);
98  vs.col(i) = Eigen::VectorXd::Random(model.nv);
99  as.col(i) = Eigen::VectorXd::Random(model.nv);
100  taus.col(i) = Eigen::VectorXd::Random(model.nv);
101  }
102 
103  ModelPool pool(model,NUM_THREADS);
104 
105  timer.tic();
106  SMOOTH(NBT)
107  {
108  for(Eigen::DenseIndex i = 0; i < BATCH_SIZE; ++i)
109  res.col(i) = rnea(model,data,qs.col(i),vs.col(i),as.col(i));
110  }
111  std::cout << "mean RNEA = \t\t\t\t"; timer.toc(std::cout,NBT*BATCH_SIZE);
112 
113  for(int num_threads = 1; num_threads <= NUM_THREADS; ++num_threads)
114  {
115  timer.tic();
116  SMOOTH(NBT)
117  {
118  rnea(num_threads,pool,qs,vs,as,res);
119  }
120  double elapsed = timer.toc()/(NBT*BATCH_SIZE);
121  std::stringstream ss;
122  ss << "mean RNEA pool (";
123  ss << num_threads;
124  ss << " threads) = \t\t";
125  ss << elapsed << " us" << std::endl;
126  std::cout << ss.str();
127  }
128 
129  std::cout << "--" << std::endl;
130 
131  timer.tic();
132  SMOOTH(NBT)
133  {
134  for(Eigen::DenseIndex i = 0; i < BATCH_SIZE; ++i)
135  res.col(i) = aba(model,data,qs.col(i),vs.col(i),taus.col(i));
136  }
137  std::cout << "mean ABA = \t\t\t\t"; timer.toc(std::cout,NBT*BATCH_SIZE);
138 
139  for(int num_threads = 1; num_threads <= NUM_THREADS; ++num_threads)
140  {
141  timer.tic();
142  SMOOTH(NBT)
143  {
144  aba(num_threads,pool,qs,vs,taus,res);
145  }
146  double elapsed = timer.toc()/(NBT*BATCH_SIZE);
147  std::stringstream ss;
148  ss << "mean ABA pool (";
149  ss << num_threads;
150  ss << " threads) = \t\t";
151  ss << elapsed << " us" << std::endl;
152  std::cout << ss.str();
153  }
154 
155 #ifdef PINOCCHIO_WITH_HPP_FCL
156  std::cout << "--" << std::endl;
157  const int NBT_COLLISION = math::max(NBT,1);
158  timer.tic();
159  SMOOTH((size_t)NBT_COLLISION)
160  {
161  computeCollisions(model,data,geometry_model,geometry_data,q_vec[_smooth]);
162  }
163  std::cout << "non parallel collision = \t\t\t"; timer.toc(std::cout,NBT_COLLISION);
164 
165  for(int num_threads = 1; num_threads <= NUM_THREADS; ++num_threads)
166  {
167  timer.tic();
168  SMOOTH((size_t)NBT_COLLISION)
169  {
170  computeCollisions(num_threads,model,data,geometry_model,geometry_data,q_vec[_smooth]);
171  }
172  double elapsed = timer.toc()/(NBT_COLLISION);
173  std::stringstream ss;
174  ss << "parallel collision (";
175  ss << num_threads;
176  ss << " threads) = \t\t";
177  ss << elapsed << " us" << std::endl;
178  std::cout << ss.str();
179  }
180 
181  std::cout << "--" << std::endl;
182  GeometryPool geometry_pool(model,geometry_model,NUM_THREADS);
183  VectorXb collision_res(BATCH_SIZE);
184  collision_res.fill(false);
185 
186  timer.tic();
187  SMOOTH((size_t)(NBT_COLLISION/BATCH_SIZE))
188  {
189  for(Eigen::DenseIndex i = 0; i < BATCH_SIZE; ++i)
190  computeCollisions(model,data,geometry_model,geometry_data,qs.col(i));
191  }
192  std::cout << "non parallel collision = \t\t\t"; timer.toc(std::cout,NBT_COLLISION);
193 
194  for(int num_threads = 1; num_threads <= NUM_THREADS; ++num_threads)
195  {
196  timer.tic();
197  SMOOTH((size_t)(NBT_COLLISION/BATCH_SIZE))
198  {
199  computeCollisions(num_threads,geometry_pool,qs,collision_res);
200  }
201  double elapsed = timer.toc()/(NBT_COLLISION);
202  std::stringstream ss;
203  ss << "pool parallel collision (";
204  ss << num_threads;
205  ss << " threads) = \t\t";
206  ss << elapsed << " us" << std::endl;
207  std::cout << ss.str();
208  }
209 #endif
210 
211  std::cout << "--" << std::endl;
212  return 0;
213 }
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)
The Articulated-Body algorithm. It computes the forward dynamics, aka the joint accelerations given t...
int main(int, const char **)
double toc()
Definition: timer.hpp:68
void removeCollisionPairs(const ModelTpl< Scalar, Options, JointCollectionTpl > &model, GeometryModel &geom_model, const std::string &filename, const bool verbose=false)
Deactive all possible collision pairs mentioned in the SRDF file. It throws if the SRDF file is incor...
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...
AD< Scalar > max(const AD< Scalar > &x, const AD< Scalar > &y)
std::vector< bool > activeCollisionPairs
Vector of collision pairs.
void randomConfiguration(const ModelTpl< Scalar, Options, JointCollectionTpl > &model, const Eigen::MatrixBase< ConfigVectorIn1 > &lowerLimits, const Eigen::MatrixBase< ConfigVectorIn2 > &upperLimits, const Eigen::MatrixBase< ReturnType > &qout)
Generate a configuration vector uniformly sampled among provided limits.
#define PINOCCHIO_MODEL_DIR
void tic()
Definition: timer.hpp:63
bool computeCollisions(const int num_threads, const GeometryModel &geom_model, GeometryData &geom_data, const bool stopAtFirstCollision=false)
std::string name
Model name;.
Eigen::Matrix< bool, Eigen::Dynamic, 1 > VectorXb
GeometryModel & buildGeom(const ModelTpl< Scalar, Options, JointCollectionTpl > &model, const std::string &filename, const GeometryType type, GeometryModel &geom_model, const std::vector< std::string > &package_paths=std::vector< std::string >(), ::hpp::fcl::MeshLoaderPtr mesh_loader=::hpp::fcl::MeshLoaderPtr())
Build The GeometryModel from a URDF file. Search for meshes in the directories specified by the user ...
#define PINOCCHIO_ALIGNED_STD_VECTOR(Type)
int BATCH_SIZE
Definition: continuous.py:34
#define SMOOTH(s)
Definition: timer.hpp:38
ModelTpl< Scalar, Options, JointCollectionTpl > & buildModel(const std::string &filename, const typename ModelTpl< Scalar, Options, JointCollectionTpl >::JointModel &rootJoint, ModelTpl< Scalar, Options, JointCollectionTpl > &model, const bool verbose=false)
Build the model from a URDF file with a particular joint as root of the model tree inside the model g...
void addAllCollisionPairs()
Add all possible collision pairs.
string srdf_filename
Definition: collisions.py:25
Main pinocchio namespace.
Definition: timings.cpp:28
res
int nv
Dimension of the velocity vector space.
filename
JointModelFreeFlyerTpl< double > JointModelFreeFlyer
Eigen::Matrix< Scalar, Eigen::Dynamic, 1 > VectorXd
Definition: conversions.cpp:14
int nq
Dimension of the configuration vector representation.


pinocchio
Author(s):
autogenerated on Fri Jun 23 2023 02:38:33