timings.cpp
Go to the documentation of this file.
1 //
2 // Copyright (c) 2015-2020 CNRS INRIA
3 //
4 
5 #include "pinocchio/multibody/model.hpp"
6 #include "pinocchio/multibody/data.hpp"
7 
8 #include "pinocchio/algorithm/joint-configuration.hpp"
9 #include "pinocchio/algorithm/frames.hpp"
10 #include "pinocchio/algorithm/crba.hpp"
11 #include "pinocchio/algorithm/centroidal.hpp"
12 #include "pinocchio/algorithm/aba.hpp"
13 #include "pinocchio/algorithm/rnea.hpp"
14 #include "pinocchio/algorithm/cholesky.hpp"
15 #include "pinocchio/algorithm/jacobian.hpp"
16 #include "pinocchio/algorithm/center-of-mass.hpp"
17 #include "pinocchio/algorithm/compute-all-terms.hpp"
18 #include "pinocchio/algorithm/kinematics.hpp"
19 
20 #include "pinocchio/parsers/urdf.hpp"
21 #include "pinocchio/parsers/sample-models.hpp"
22 
23 #include <iostream>
24 
25 #include "pinocchio/utils/timer.hpp"
26 
27 #include <Eigen/StdVector>
28 EIGEN_DEFINE_STL_VECTOR_SPECIALIZATION(Eigen::VectorXd)
29 
30 namespace pinocchio
31 {
32  template<typename Scalar, int Options, template<typename,int> class JointCollectionTpl>
34  : fusion::JointUnaryVisitorBase< EmptyForwardStepUnaryVisit<Scalar,Options,JointCollectionTpl> >
35  {
38 
40 
41  template<typename JointModel>
42  static void algo(const JointModelBase<JointModel> &,
44  )
45  { // do nothing
46  }
47 
48  };
49 
50  template<typename Scalar, int Options, template<typename,int> class JointCollectionTpl>
53  {
54  assert(model.check(data) && "data is not consistent with model.");
55 
58 
59  for(JointIndex i=1; i < (JointIndex)model.njoints; ++i)
60  {
61  Algo::run(model.joints[i],data.joints[i]);
62  }
63  }
64 
65  template<typename Scalar, int Options, template<typename,int> class JointCollectionTpl>
67  : fusion::JointUnaryVisitorBase< EmptyForwardStepUnaryVisitNoData<Scalar,Options,JointCollectionTpl> >
68  {
71 
73 
74  template<typename JointModel>
75  EIGEN_DONT_INLINE
76  static void algo(const JointModelBase<JointModel> &)
77  { // do nothing
78  }
79 
80  };
81 
82  template<typename Scalar, int Options, template<typename,int> class JointCollectionTpl>
85  {
87  assert(model.check(data) && "data is not consistent with model.");
88 
91 
92  for(JointIndex i=1; i < (JointIndex)model.njoints; ++i)
93  {
94  Algo::run(model.joints[i]);
95  }
96  }
97 
98  template<typename Scalar, int Options, template<typename,int> class JointCollectionTpl>
100  : fusion::JointBinaryVisitorBase< EmptyForwardStepBinaryVisit<Scalar,Options,JointCollectionTpl> >
101  {
104 
106 
107  template<typename JointModel1, typename JointModel2>
108  EIGEN_DONT_INLINE
109  static void algo(const JointModelBase<JointModel1> &,
113  { // do nothing
114  }
115 
116  };
117 
118  template<typename Scalar, int Options, template<typename,int> class JointCollectionTpl>
121  {
122  assert(model.check(data) && "data is not consistent with model.");
123 
126 
127  for(JointIndex i=1; i < (JointIndex)model.njoints; ++i)
128  {
129  Algo::run(model.joints[i],model.joints[i],
130  data.joints[i],data.joints[i]);
131  }
132  }
133 
134  template<typename Scalar, int Options, template<typename,int> class JointCollectionTpl>
136  : fusion::JointBinaryVisitorBase< EmptyForwardStepBinaryVisitNoData<Scalar,Options,JointCollectionTpl> >
137  {
140 
142 
143  template<typename JointModel1, typename JointModel2>
144  EIGEN_DONT_INLINE
145  static void algo(const JointModelBase<JointModel1> &,
147  { // do nothing
148  }
149 
150  };
151 
152  template<typename Scalar, int Options, template<typename,int> class JointCollectionTpl>
155  {
157  assert(model.check(data) && "data is not consistent with model.");
158 
161 
162  for(JointIndex i=1; i < (JointIndex)model.njoints; ++i)
163  {
164  Algo::run(model.joints[i],model.joints[i]);
165  }
166  }
167 }
168 
169 int main(int argc, const char ** argv)
170 {
171  using namespace Eigen;
172  using namespace pinocchio;
173 
175  #ifdef NDEBUG
176  const int NBT = 1000*100;
177  #else
178  const int NBT = 1;
179  std::cout << "(the time score in debug mode is not relevant) " << std::endl;
180  #endif
181 
183 
184  std::string filename = PINOCCHIO_MODEL_DIR + std::string("/simple_humanoid.urdf");
185  if(argc>1) filename = argv[1];
186 
187  bool with_ff = true;
188  if(argc>2)
189  {
190  const std::string ff_option = argv[2];
191  if(ff_option == "-no-ff")
192  with_ff = false;
193  }
194 
195  if( filename == "HS")
197  else
198  if(with_ff)
200  else
201  pinocchio::urdf::buildModel(filename,model);
202  std::cout << "nq = " << model.nq << std::endl;
203 
204 
205 
206  pinocchio::Data data(model);
207  const VectorXd qmax = Eigen::VectorXd::Ones(model.nq);
208 
212  for(size_t i=0;i<NBT;++i)
213  {
214  qs[i] = randomConfiguration(model,-qmax,qmax);
215  qdots[i] = Eigen::VectorXd::Random(model.nv);
216  qddots[i] = Eigen::VectorXd::Random(model.nv);
217  }
218 
219 
220  timer.tic();
221  SMOOTH(NBT)
222  {
223  rnea(model,data,qs[_smooth],qdots[_smooth],qddots[_smooth]);
224  }
225  std::cout << "RNEA = \t\t"; timer.toc(std::cout,NBT);
226 
227  timer.tic();
228  SMOOTH(NBT)
229  {
230  nonLinearEffects(model,data,qs[_smooth],qdots[_smooth]);
231  }
232  std::cout << "NLE = \t\t"; timer.toc(std::cout,NBT);
233 
234  timer.tic();
235  SMOOTH(NBT)
236  {
237  rnea(model,data,qs[_smooth],qdots[_smooth],Eigen::VectorXd::Zero(model.nv));
238  }
239  std::cout << "NLE via RNEA = \t\t"; timer.toc(std::cout,NBT);
240 
241  timer.tic();
242  SMOOTH(NBT)
243  {
244  crba(model,data,qs[_smooth]);
245  }
246  std::cout << "CRBA = \t\t"; timer.toc(std::cout,NBT);
247 
248  timer.tic();
249  SMOOTH(NBT)
250  {
251  crbaMinimal(model,data,qs[_smooth]);
252  }
253  std::cout << "CRBA minimal = \t\t"; timer.toc(std::cout,NBT);
254 
255  timer.tic();
256  SMOOTH(NBT)
257  {
258  computeAllTerms(model,data,qs[_smooth],qdots[_smooth]);
259  }
260  std::cout << "computeAllTerms = \t\t"; timer.toc(std::cout,NBT);
261 
262  double total = 0;
263  SMOOTH(NBT)
264  {
265  crba(model,data,qs[_smooth]);
266  timer.tic();
267  cholesky::decompose(model,data);
268  total += timer.toc(timer.DEFAULT_UNIT);
269  }
270  std::cout << "Branch Induced Sparsity Cholesky = \t" << (total/NBT)
271  << " " << timer.unitName(timer.DEFAULT_UNIT) <<std::endl;
272 
273  total = 0;
274  Eigen::LDLT<Eigen::MatrixXd> Mldlt(data.M);
275  SMOOTH(NBT)
276  {
277  crba(model,data,qs[_smooth]);
278  data.M.triangularView<Eigen::StrictlyLower>()
279  = data.M.transpose().triangularView<Eigen::StrictlyLower>();
280  timer.tic();
281  Mldlt.compute(data.M);
282  total += timer.toc(timer.DEFAULT_UNIT);
283  }
284  std::cout << "Dense Eigen Cholesky = \t" << (total/NBT)
285  << " " << timer.unitName(timer.DEFAULT_UNIT) <<std::endl;
286 
287  timer.tic();
288  SMOOTH(NBT)
289  {
290  computeJointJacobians(model,data,qs[_smooth]);
291  }
292  std::cout << "Jacobian = \t"; timer.toc(std::cout,NBT);
293 
294  timer.tic();
295  SMOOTH(NBT)
296  {
297  computeJointJacobiansTimeVariation(model,data,qs[_smooth],qdots[_smooth]);
298  }
299  std::cout << "Jacobian Time Variation = \t"; timer.toc(std::cout,NBT);
300 
301  timer.tic();
302  SMOOTH(NBT)
303  {
304  jacobianCenterOfMass(model,data,qs[_smooth],true);
305  }
306  std::cout << "COM+Jcom = \t"; timer.toc(std::cout,NBT);
307 
308  timer.tic();
309  SMOOTH(NBT)
310  {
311  centerOfMass(model,data,qs[_smooth], qdots[_smooth], qddots[_smooth], true);
312  }
313  std::cout << "COM+vCOM+aCOM = \t"; timer.toc(std::cout,NBT);
314 
315  timer.tic();
316  SMOOTH(NBT)
317  {
318  forwardKinematics(model,data,qs[_smooth]);
319  }
320  std::cout << "Zero Order Kinematics = \t"; timer.toc(std::cout,NBT);
321 
322 
323  timer.tic();
324  SMOOTH(NBT)
325  {
326  forwardKinematics(model,data,qs[_smooth],qdots[_smooth]);
327  }
328  std::cout << "First Order Kinematics = \t"; timer.toc(std::cout,NBT);
329 
330  timer.tic();
331  SMOOTH(NBT)
332  {
333  forwardKinematics(model,data,qs[_smooth],qdots[_smooth], qddots[_smooth]);
334  }
335  std::cout << "Second Order Kinematics = \t"; timer.toc(std::cout,NBT);
336 
337  total = 0.;
338  SMOOTH(NBT)
339  {
340  forwardKinematics(model,data,qs[_smooth]);
341  timer.tic();
342  updateFramePlacements(model, data);
343  total += timer.toc(timer.DEFAULT_UNIT);
344  }
345  std::cout << "Update Frame Placement = \t" << (total/NBT)
346  << " " << timer.unitName(timer.DEFAULT_UNIT) << std::endl;
347 
348 
349  timer.tic();
350  SMOOTH(NBT)
351  {
352  framesForwardKinematics(model,data, qs[_smooth]);
353  }
354  std::cout << "Zero Order Frames Kinematics = \t"; timer.toc(std::cout,NBT);
355 
356  timer.tic();
357  SMOOTH(NBT)
358  {
359  ccrba(model,data,qs[_smooth],qdots[_smooth]);
360  }
361  std::cout << "CCRBA = \t"; timer.toc(std::cout,NBT);
362 
363  timer.tic();
364  SMOOTH(NBT)
365  {
366  aba(model,data,qs[_smooth],qdots[_smooth], qddots[_smooth]);
367  }
368  std::cout << "ABA = \t"; timer.toc(std::cout,NBT);
369 
370  timer.tic();
371  SMOOTH(NBT)
372  {
373  emptyForwardPassUnaryVisit(model,data);
374  }
375  std::cout << "Empty Forward Pass Unary visit (no computations) = \t"; timer.toc(std::cout,NBT);
376 
377  timer.tic();
378  SMOOTH(NBT)
379  {
381  }
382  std::cout << "Empty Forward Pass Unary visit No Data (no computations) = \t"; timer.toc(std::cout,NBT);
383 
384  timer.tic();
385  SMOOTH(NBT)
386  {
387  emptyForwardPassBinaryVisit(model,data);
388  }
389  std::cout << "Empty Forward Pass Binary visit (no computations) = \t"; timer.toc(std::cout,NBT);
390 
391  timer.tic();
392  SMOOTH(NBT)
393  {
395  }
396  std::cout << "Empty Forward Pass Binary visit No Data (no computations) = \t"; timer.toc(std::cout,NBT);
397 
398  timer.tic();
399  SMOOTH(NBT)
400  {
401  computeCoriolisMatrix(model,data,qs[_smooth],qdots[_smooth]);
402  }
403  std::cout << "Coriolis Matrix = \t"; timer.toc(std::cout,NBT);
404 
405  timer.tic();
406  SMOOTH(NBT)
407  {
408  computeMinverse(model,data,qs[_smooth]);
409  }
410  std::cout << "Minv = \t"; timer.toc(std::cout,NBT);
411 
412  std::cout << "--" << std::endl;
413  return 0;
414 }
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...
ModelTpl< Scalar, Options, JointCollectionTpl > Model
Definition: timings.cpp:69
ModelTpl< Scalar, Options, JointCollectionTpl > Model
Definition: timings.cpp:102
void computeAllTerms(const ModelTpl< Scalar, Options, JointCollectionTpl > &model, DataTpl< Scalar, Options, JointCollectionTpl > &data, const Eigen::MatrixBase< ConfigVectorType > &q, const Eigen::MatrixBase< TangentVectorType > &v)
Computes efficiently all the terms needed for dynamic simulation. It is equivalent to the call at the...
void emptyForwardPassUnaryVisit(const ModelTpl< Scalar, Options, JointCollectionTpl > &model, DataTpl< Scalar, Options, JointCollectionTpl > &data)
Definition: timings.cpp:51
double toc()
Definition: timer.hpp:68
const DataTpl< Scalar, Options, JointCollectionTpl >::Matrix3x & jacobianCenterOfMass(const ModelTpl< Scalar, Options, JointCollectionTpl > &model, DataTpl< Scalar, Options, JointCollectionTpl > &data, const Eigen::MatrixBase< ConfigVectorType > &q, const bool computeSubtreeComs=true)
Computes both the jacobian and the the center of mass position of a given model according to a partic...
Unit DEFAULT_UNIT
Definition: timer.hpp:50
JointModelVector joints
Model of joint i, encapsulated in a JointModelAccessor.
const DataTpl< Scalar, Options, JointCollectionTpl >::MatrixXs & crba(const ModelTpl< Scalar, Options, JointCollectionTpl > &model, DataTpl< Scalar, Options, JointCollectionTpl > &data, const Eigen::MatrixBase< ConfigVectorType > &q)
Computes the upper triangular part of the joint space inertia matrix M by using the Composite Rigid B...
int main(int argc, const char **argv)
Definition: timings.cpp:169
#define PINOCCHIO_UNUSED_VARIABLE(var)
Helper to declare that a parameter is unused.
Definition: src/macros.hpp:51
DataTpl< Scalar, Options, JointCollectionTpl > Data
Definition: timings.cpp:70
const DataTpl< Scalar, Options, JointCollectionTpl >::RowMatrixXs & computeMinverse(const ModelTpl< Scalar, Options, JointCollectionTpl > &model, DataTpl< Scalar, Options, JointCollectionTpl > &data, const Eigen::MatrixBase< ConfigVectorType > &q)
Computes the inverse of the joint space inertia matrix using Articulated Body formulation.
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...
Base structure for Binary visitation of two JointModels. This structure provides runners to call the ...
DataTpl< Scalar, Options, JointCollectionTpl > Data
Definition: timings.cpp:139
const DataTpl< Scalar, Options, JointCollectionTpl >::MatrixXs & decompose(const ModelTpl< Scalar, Options, JointCollectionTpl > &model, DataTpl< Scalar, Options, JointCollectionTpl > &data)
Compute the Cholesky decomposition of the joint space inertia matrix M contained in data...
int njoints
Number of joints.
static std::string unitName(Unit u)
Definition: timer.hpp:52
JointDataVector joints
Vector of pinocchio::JointData associated to the pinocchio::JointModel stored in model, encapsulated in JointDataAccessor.
bool check(const AlgorithmCheckerBase< D > &checker=AlgorithmCheckerBase< D >()) const
Check the validity of the attributes of Model with respect to the specification of some algorithms...
DataTpl< Scalar, Options, JointCollectionTpl > Data
Definition: timings.cpp:37
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.
data
#define PINOCCHIO_MODEL_DIR
void tic()
Definition: timer.hpp:63
static EIGEN_DONT_INLINE void algo(const JointModelBase< JointModel > &)
Definition: timings.cpp:76
void emptyForwardPassUnaryVisitNoData(const ModelTpl< Scalar, Options, JointCollectionTpl > &model, DataTpl< Scalar, Options, JointCollectionTpl > &data)
Definition: timings.cpp:83
void forwardKinematics(const ModelTpl< Scalar, Options, JointCollectionTpl > &model, DataTpl< Scalar, Options, JointCollectionTpl > &data, const Eigen::MatrixBase< ConfigVectorType > &q)
Update the joint placements according to the current joint configuration.
const DataTpl< Scalar, Options, JointCollectionTpl >::Matrix6x & ccrba(const ModelTpl< Scalar, Options, JointCollectionTpl > &model, DataTpl< Scalar, Options, JointCollectionTpl > &data, const Eigen::MatrixBase< ConfigVectorType > &q, const Eigen::MatrixBase< TangentVectorType > &v)
Computes the Centroidal Momentum Matrix, the Composite Ridig Body Inertia as well as the centroidal m...
static EIGEN_DONT_INLINE void algo(const JointModelBase< JointModel1 > &, const JointModelBase< JointModel2 > &)
Definition: timings.cpp:145
Base structure for Unary visitation of a JointModel. This structure provides runners to call the righ...
static EIGEN_DONT_INLINE void algo(const JointModelBase< JointModel1 > &, const JointModelBase< JointModel2 > &, JointDataBase< typename JointModel1::JointDataDerived > &, JointDataBase< typename JointModel2::JointDataDerived > &)
Definition: timings.cpp:109
MatrixXs M
The joint space inertia matrix (a square matrix of dim model.nv).
const DataTpl< Scalar, Options, JointCollectionTpl >::MatrixXs & crbaMinimal(const ModelTpl< Scalar, Options, JointCollectionTpl > &model, DataTpl< Scalar, Options, JointCollectionTpl > &data, const Eigen::MatrixBase< ConfigVectorType > &q)
Computes the upper triangular part of the joint space inertia matrix M by using the Composite Rigid B...
#define PINOCCHIO_ALIGNED_STD_VECTOR(Type)
ModelTpl< Scalar, Options, JointCollectionTpl > Model
Definition: timings.cpp:36
const DataTpl< Scalar, Options, JointCollectionTpl >::Matrix6x & computeJointJacobiansTimeVariation(const ModelTpl< Scalar, Options, JointCollectionTpl > &model, DataTpl< Scalar, Options, JointCollectionTpl > &data, const Eigen::MatrixBase< ConfigVectorType > &q, const Eigen::MatrixBase< TangentVectorType > &v)
Computes the full model Jacobian variations with respect to time. It corresponds to dJ/dt which depen...
#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...
Main pinocchio namespace.
Definition: timings.cpp:30
const DataTpl< Scalar, Options, JointCollectionTpl >::Matrix6x & computeJointJacobians(const ModelTpl< Scalar, Options, JointCollectionTpl > &model, DataTpl< Scalar, Options, JointCollectionTpl > &data, const Eigen::MatrixBase< ConfigVectorType > &q)
Computes the full model Jacobian, i.e. the stack of all motion subspace expressed in the world frame...
int nv
Dimension of the velocity vector space.
void emptyForwardPassBinaryVisitNoData(const ModelTpl< Scalar, Options, JointCollectionTpl > &model, DataTpl< Scalar, Options, JointCollectionTpl > &data)
Definition: timings.cpp:153
void updateFramePlacements(const ModelTpl< Scalar, Options, JointCollectionTpl > &model, DataTpl< Scalar, Options, JointCollectionTpl > &data)
Updates the position of each frame contained in the model.
const DataTpl< Scalar, Options, JointCollectionTpl >::MatrixXs & computeCoriolisMatrix(const ModelTpl< Scalar, Options, JointCollectionTpl > &model, DataTpl< Scalar, Options, JointCollectionTpl > &data, const Eigen::MatrixBase< ConfigVectorType > &q, const Eigen::MatrixBase< TangentVectorType > &v)
Computes the Coriolis Matrix of the Lagrangian dynamics:
const DataTpl< Scalar, Options, JointCollectionTpl >::Vector3 & centerOfMass(const ModelTpl< Scalar, Options, JointCollectionTpl > &model, DataTpl< Scalar, Options, JointCollectionTpl > &data, const Eigen::MatrixBase< ConfigVectorType > &q, const bool computeSubtreeComs=true)
Computes the center of mass position of a given model according to a particular joint configuration...
DataTpl< Scalar, Options, JointCollectionTpl > Data
Definition: timings.cpp:103
JointModelFreeFlyerTpl< double > JointModelFreeFlyer
static void algo(const JointModelBase< JointModel > &, JointDataBase< typename JointModel::JointDataDerived > &)
Definition: timings.cpp:42
const DataTpl< Scalar, Options, JointCollectionTpl >::TangentVectorType & nonLinearEffects(const ModelTpl< Scalar, Options, JointCollectionTpl > &model, DataTpl< Scalar, Options, JointCollectionTpl > &data, const Eigen::MatrixBase< ConfigVectorType > &q, const Eigen::MatrixBase< TangentVectorType > &v)
Computes the non-linear effects (Corriolis, centrifual and gravitationnal effects), also called the bias terms of the Lagrangian dynamics:
void emptyForwardPassBinaryVisit(const ModelTpl< Scalar, Options, JointCollectionTpl > &model, DataTpl< Scalar, Options, JointCollectionTpl > &data)
Definition: timings.cpp:119
void humanoidRandom(ModelTpl< Scalar, Options, JointCollectionTpl > &model, bool usingFF=true)
Create a humanoid kinematic tree with 6-DOF limbs and random joint placements.
Eigen::Matrix< Scalar, Eigen::Dynamic, 1 > VectorXd
Definition: conversions.cpp:14
int nq
Dimension of the configuration vector representation.
ModelTpl< Scalar, Options, JointCollectionTpl > Model
Definition: timings.cpp:138
void framesForwardKinematics(const ModelTpl< Scalar, Options, JointCollectionTpl > &model, DataTpl< Scalar, Options, JointCollectionTpl > &data, const Eigen::MatrixBase< ConfigVectorType > &q)
First calls the forwardKinematics on the model, then computes the placement of each frame...


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