timings.cpp
Go to the documentation of this file.
1 //
2 // Copyright (c) 2015-2020 CNRS INRIA
3 //
4 
7 
19 
22 
23 #include <iostream>
24 
26 
27 namespace pinocchio
28 {
29  template<typename Scalar, int Options, template<typename, int> class JointCollectionTpl>
31  : fusion::JointUnaryVisitorBase<EmptyForwardStepUnaryVisit<Scalar, Options, JointCollectionTpl>>
32  {
35 
37 
38  template<typename JointModel>
39  static void
41  { // do nothing
42  }
43  };
44 
45  template<typename Scalar, int Options, template<typename, int> class JointCollectionTpl>
49  {
50  assert(model.check(data) && "data is not consistent with model.");
51 
54 
55  for (JointIndex i = 1; i < (JointIndex)model.njoints; ++i)
56  {
57  Algo::run(model.joints[i], data.joints[i]);
58  }
59  }
60 
61  template<typename Scalar, int Options, template<typename, int> class JointCollectionTpl>
64  EmptyForwardStepUnaryVisitNoData<Scalar, Options, JointCollectionTpl>>
65  {
68 
70 
71  template<typename JointModel>
72  EIGEN_DONT_INLINE static void algo(const JointModelBase<JointModel> &)
73  { // do nothing
74  }
75  };
76 
77  template<typename Scalar, int Options, template<typename, int> class JointCollectionTpl>
81  {
83  assert(model.check(data) && "data is not consistent with model.");
84 
87 
88  for (JointIndex i = 1; i < (JointIndex)model.njoints; ++i)
89  {
90  Algo::run(model.joints[i]);
91  }
92  }
93 
94  template<typename Scalar, int Options, template<typename, int> class JointCollectionTpl>
96  : fusion::JointBinaryVisitorBase<EmptyForwardStepBinaryVisit<Scalar, Options, JointCollectionTpl>>
97  {
100 
102 
103  template<typename JointModel1, typename JointModel2>
104  EIGEN_DONT_INLINE static void algo(
109  { // do nothing
110  }
111  };
112 
113  template<typename Scalar, int Options, template<typename, int> class JointCollectionTpl>
117  {
118  assert(model.check(data) && "data is not consistent with model.");
119 
122 
123  for (JointIndex i = 1; i < (JointIndex)model.njoints; ++i)
124  {
125  Algo::run(model.joints[i], model.joints[i], data.joints[i], data.joints[i]);
126  }
127  }
128 
129  template<typename Scalar, int Options, template<typename, int> class JointCollectionTpl>
132  EmptyForwardStepBinaryVisitNoData<Scalar, Options, JointCollectionTpl>>
133  {
136 
138 
139  template<typename JointModel1, typename JointModel2>
140  EIGEN_DONT_INLINE static void
142  { // do nothing
143  }
144  };
145 
146  template<typename Scalar, int Options, template<typename, int> class JointCollectionTpl>
150  {
152  assert(model.check(data) && "data is not consistent with model.");
153 
156 
157  for (JointIndex i = 1; i < (JointIndex)model.njoints; ++i)
158  {
159  Algo::run(model.joints[i], model.joints[i]);
160  }
161  }
162 } // namespace pinocchio
163 
164 int main(int argc, const char ** argv)
165 {
166  using namespace Eigen;
167  using namespace pinocchio;
168 
170 #ifdef NDEBUG
171  const int NBT = 1000 * 100;
172 #else
173  const int NBT = 1;
174  std::cout << "(the time score in debug mode is not relevant) " << std::endl;
175 #endif
176 
178 
179  std::string filename = PINOCCHIO_MODEL_DIR + std::string("/simple_humanoid.urdf");
180  if (argc > 1)
181  filename = argv[1];
182 
183  bool with_ff = true;
184  if (argc > 2)
185  {
186  const std::string ff_option = argv[2];
187  if (ff_option == "-no-ff")
188  with_ff = false;
189  }
190 
191  if (filename == "HS")
193  else if (with_ff)
195  else
197  std::cout << "nq = " << model.nq << std::endl;
198  std::cout << "nv = " << model.nv << std::endl;
199  std::cout << "--" << std::endl;
200 
202  const VectorXd qmax = Eigen::VectorXd::Ones(model.nq);
203 
204  PINOCCHIO_ALIGNED_STD_VECTOR(VectorXd) qs(NBT);
205  PINOCCHIO_ALIGNED_STD_VECTOR(VectorXd) qdots(NBT);
206  PINOCCHIO_ALIGNED_STD_VECTOR(VectorXd) qddots(NBT);
207  PINOCCHIO_ALIGNED_STD_VECTOR(VectorXd) taus(NBT);
208  for (size_t i = 0; i < NBT; ++i)
209  {
210  qs[i] = randomConfiguration(model, -qmax, qmax);
211  qdots[i] = Eigen::VectorXd::Random(model.nv);
212  qddots[i] = Eigen::VectorXd::Random(model.nv);
213  taus[i] = Eigen::VectorXd::Random(model.nv);
214  }
215 
216  timer.tic();
217  SMOOTH(NBT)
218  {
219  rnea(model, data, qs[_smooth], qdots[_smooth], qddots[_smooth]);
220  }
221  std::cout << "RNEA = \t\t\t\t";
222  timer.toc(std::cout, NBT);
223 
224  timer.tic();
225  SMOOTH(NBT)
226  {
227  nonLinearEffects(model, data, qs[_smooth], qdots[_smooth]);
228  }
229  std::cout << "NLE = \t\t\t\t";
230  timer.toc(std::cout, NBT);
231 
232  timer.tic();
233  SMOOTH(NBT)
234  {
235  rnea(model, data, qs[_smooth], qdots[_smooth], Eigen::VectorXd::Zero(model.nv));
236  }
237  std::cout << "NLE via RNEA = \t\t\t";
238  timer.toc(std::cout, NBT);
239 
240  timer.tic();
241  SMOOTH(NBT)
242  {
243  crba(model, data, qs[_smooth], Convention::LOCAL);
244  }
245  std::cout << "CRBA (original) = \t\t";
246  timer.toc(std::cout, NBT);
247 
248  timer.tic();
249  SMOOTH(NBT)
250  {
251  crba(model, data, qs[_smooth], Convention::WORLD);
252  }
253  std::cout << "CRBA = \t\t";
254  timer.toc(std::cout, NBT);
255 
256  timer.tic();
257  SMOOTH(NBT)
258  {
259  computeAllTerms(model, data, qs[_smooth], qdots[_smooth]);
260  }
261  std::cout << "computeAllTerms = \t\t";
262  timer.toc(std::cout, NBT);
263 
264  double total = 0;
265  SMOOTH(NBT)
266  {
267  crba(model, data, qs[_smooth], Convention::WORLD);
268  timer.tic();
270  total += timer.toc(timer.DEFAULT_UNIT);
271  }
272  std::cout << "Sparse Cholesky = \t\t" << (total / NBT) << " "
273  << timer.unitName(timer.DEFAULT_UNIT) << std::endl;
274 
275  total = 0;
276  Eigen::LDLT<Eigen::MatrixXd> Mldlt(data.M);
277  SMOOTH(NBT)
278  {
279  crba(model, data, qs[_smooth], Convention::WORLD);
280  data.M.triangularView<Eigen::StrictlyLower>() =
281  data.M.transpose().triangularView<Eigen::StrictlyLower>();
282  timer.tic();
283  Mldlt.compute(data.M);
284  total += timer.toc(timer.DEFAULT_UNIT);
285  }
286  std::cout << "Dense Cholesky = \t\t" << (total / NBT) << " " << timer.unitName(timer.DEFAULT_UNIT)
287  << std::endl;
288 
289  timer.tic();
290  SMOOTH(NBT)
291  {
292  computeJointJacobians(model, data, qs[_smooth]);
293  }
294  std::cout << "Jacobian = \t\t\t";
295  timer.toc(std::cout, NBT);
296 
297  timer.tic();
298  SMOOTH(NBT)
299  {
300  computeJointJacobiansTimeVariation(model, data, qs[_smooth], qdots[_smooth]);
301  }
302  std::cout << "Jacobian Derivative = \t\t";
303  timer.toc(std::cout, NBT);
304 
305  timer.tic();
306  SMOOTH(NBT)
307  {
308  jacobianCenterOfMass(model, data, qs[_smooth], true);
309  }
310  std::cout << "COM+Jcom = \t\t\t";
311  timer.toc(std::cout, NBT);
312 
313  timer.tic();
314  SMOOTH(NBT)
315  {
316  centerOfMass(model, data, qs[_smooth], qdots[_smooth], qddots[_smooth], true);
317  }
318  std::cout << "COM+vCOM+aCOM = \t\t";
319  timer.toc(std::cout, NBT);
320 
321  timer.tic();
322  SMOOTH(NBT)
323  {
324  forwardKinematics(model, data, qs[_smooth]);
325  }
326  std::cout << "Forward Kinematics(q) = \t";
327  timer.toc(std::cout, NBT);
328 
329  timer.tic();
330  SMOOTH(NBT)
331  {
332  forwardKinematics(model, data, qs[_smooth], qdots[_smooth]);
333  }
334  std::cout << "Forward Kinematics(q,v) = \t";
335  timer.toc(std::cout, NBT);
336 
337  timer.tic();
338  SMOOTH(NBT)
339  {
340  forwardKinematics(model, data, qs[_smooth], qdots[_smooth], qddots[_smooth]);
341  }
342  std::cout << "Forward Kinematics(q,v,a) = \t";
343  timer.toc(std::cout, NBT);
344 
345  timer.tic();
346  SMOOTH(NBT)
347  {
348  framesForwardKinematics(model, data, qs[_smooth]);
349  }
350  std::cout << "Frame Placement(q) = \t\t";
351  timer.toc(std::cout, NBT);
352 
353  total = 0.;
354  SMOOTH(NBT)
355  {
356  forwardKinematics(model, data, qs[_smooth]);
357  timer.tic();
359  total += timer.toc(timer.DEFAULT_UNIT);
360  }
361  std::cout << "Update Frame Placement = \t" << (total / NBT) << " "
362  << timer.unitName(timer.DEFAULT_UNIT) << std::endl;
363 
364  timer.tic();
365  SMOOTH(NBT)
366  {
367  ccrba(model, data, qs[_smooth], qdots[_smooth]);
368  }
369  std::cout << "CCRBA = \t\t\t";
370  timer.toc(std::cout, NBT);
371 
372  timer.tic();
373  SMOOTH(NBT)
374  {
375  aba(model, data, qs[_smooth], qdots[_smooth], taus[_smooth], Convention::LOCAL);
376  }
377  std::cout << "ABA (minimal) = \t\t";
378  timer.toc(std::cout, NBT);
379 
380  timer.tic();
381  SMOOTH(NBT)
382  {
383  aba(model, data, qs[_smooth], qdots[_smooth], taus[_smooth], Convention::WORLD);
384  }
385  std::cout << "ABA = \t\t";
386  timer.toc(std::cout, NBT);
387 
388  timer.tic();
389  SMOOTH(NBT)
390  {
391  computeCoriolisMatrix(model, data, qs[_smooth], qdots[_smooth]);
392  }
393  std::cout << "Coriolis Matrix = \t\t";
394  timer.toc(std::cout, NBT);
395 
396  timer.tic();
397  SMOOTH(NBT)
398  {
399  computeMinverse(model, data, qs[_smooth]);
400  }
401  std::cout << "Minv(q) = \t\t\t";
402  timer.toc(std::cout, NBT);
403 
404  total = 0;
405  SMOOTH(NBT)
406  {
407  aba(model, data, qs[_smooth], qdots[_smooth], taus[_smooth], Convention::WORLD);
408  timer.tic();
410  total += timer.toc(timer.DEFAULT_UNIT);
411  }
412  std::cout << "Minv() = \t\t\t" << (total / NBT) << " " << timer.unitName(timer.DEFAULT_UNIT)
413  << std::endl;
414  std::cout << "--" << std::endl;
415 
416  timer.tic();
417  SMOOTH(NBT)
418  {
420  }
421  std::cout << "Forward Pass(jmodel,jdata) = \t\t\t";
422  timer.toc(std::cout, NBT);
423 
424  timer.tic();
425  SMOOTH(NBT)
426  {
428  }
429  std::cout << "Forward Pass(jmodel) = \t\t\t\t";
430  timer.toc(std::cout, NBT);
431 
432  timer.tic();
433  SMOOTH(NBT)
434  {
436  }
437  std::cout << "Forward Pass(jmodel1,jmodel2,jdata1,jdata2) = \t";
438  timer.toc(std::cout, NBT);
439 
440  timer.tic();
441  SMOOTH(NBT)
442  {
444  }
445  std::cout << "Forward Pass(jmodel1,jmodel2) = \t\t";
446  timer.toc(std::cout, NBT);
447 
448  std::cout << "--" << std::endl;
449  return 0;
450 }
pinocchio::EmptyForwardStepBinaryVisit::Data
DataTpl< Scalar, Options, JointCollectionTpl > Data
Definition: timings.cpp:99
pinocchio::WORLD
@ WORLD
Definition: multibody/fwd.hpp:48
pinocchio::emptyForwardPassUnaryVisit
void emptyForwardPassUnaryVisit(const ModelTpl< Scalar, Options, JointCollectionTpl > &model, DataTpl< Scalar, Options, JointCollectionTpl > &data)
Definition: timings.cpp:46
frames.hpp
PinocchioTicToc::toc
double toc()
Definition: timer.hpp:88
pinocchio::EmptyForwardStepUnaryVisit::Data
DataTpl< Scalar, Options, JointCollectionTpl > Data
Definition: timings.cpp:34
Eigen
pinocchio::DataTpl
Definition: context/generic.hpp:25
pinocchio::forwardKinematics
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.
compute-all-terms.hpp
omniidl_be_python_with_docstring.run
def run(tree, args)
Definition: cmake/hpp/idl/omniidl_be_python_with_docstring.py:140
pinocchio::JointModelBase
Definition: joint-model-base.hpp:75
pinocchio::EmptyForwardStepBinaryVisit::ArgsType
fusion::NoArg ArgsType
Definition: timings.cpp:101
pinocchio::EmptyForwardStepUnaryVisitNoData::Model
ModelTpl< Scalar, Options, JointCollectionTpl > Model
Definition: timings.cpp:66
pinocchio::EmptyForwardStepBinaryVisitNoData::Model
ModelTpl< Scalar, Options, JointCollectionTpl > Model
Definition: timings.cpp:134
pinocchio::JointDataBase
Definition: joint-data-base.hpp:161
inverse-kinematics.i
int i
Definition: inverse-kinematics.py:17
kinematics.hpp
model.hpp
setup.data
data
Definition: cmake/cython/setup.in.py:48
pinocchio::buildModels::humanoidRandom
void humanoidRandom(ModelTpl< Scalar, Options, JointCollectionTpl > &model, bool usingFF=true)
Create a humanoid kinematic tree with 6-DOF limbs and random joint placements.
pinocchio::fusion::JointBinaryVisitorBase
Base structure for Binary visitation of two JointModels. This structure provides runners to call the ...
Definition: joint-binary-visitor.hpp:27
pinocchio::python::context::JointModelFreeFlyer
JointModelFreeFlyerTpl< Scalar > JointModelFreeFlyer
Definition: bindings/python/context/generic.hpp:126
pinocchio::crba
const DataTpl< Scalar, Options, JointCollectionTpl >::MatrixXs & crba(const ModelTpl< Scalar, Options, JointCollectionTpl > &model, DataTpl< Scalar, Options, JointCollectionTpl > &data, const Eigen::MatrixBase< ConfigVectorType > &q, const Convention convention=Convention::LOCAL)
Computes the upper triangular part of the joint space inertia matrix M by using the Composite Rigid B...
pinocchio::computeJointJacobiansTimeVariation
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...
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...
pinocchio::computeJointJacobians
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....
pinocchio::EmptyForwardStepBinaryVisit
Definition: timings.cpp:95
pinocchio::EmptyForwardStepBinaryVisitNoData
Definition: timings.cpp:130
PinocchioTicToc::unitName
static std::string unitName(Unit u)
Definition: timer.hpp:58
PinocchioTicToc::DEFAULT_UNIT
Unit DEFAULT_UNIT
Definition: timer.hpp:56
pinocchio::randomConfiguration
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.
Definition: joint-configuration.hpp:315
pinocchio::EmptyForwardStepUnaryVisitNoData::Data
DataTpl< Scalar, Options, JointCollectionTpl > Data
Definition: timings.cpp:67
pinocchio::fusion::JointUnaryVisitorBase
Base structure for Unary visitation of a JointModel. This structure provides runners to call the righ...
Definition: joint-unary-visitor.hpp:25
rnea.hpp
timer.hpp
pinocchio::EmptyForwardStepBinaryVisitNoData::ArgsType
fusion::NoArg ArgsType
Definition: timings.cpp:137
pinocchio::computeMinverse
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.
aba.hpp
anymal-simulation.model
model
Definition: anymal-simulation.py:8
pinocchio::ModelTpl::JointIndex
pinocchio::JointIndex JointIndex
Definition: multibody/model.hpp:67
center-of-mass.hpp
SMOOTH
#define SMOOTH(s)
Definition: timer.hpp:38
joint-configuration.hpp
pinocchio::updateFramePlacements
void updateFramePlacements(const ModelTpl< Scalar, Options, JointCollectionTpl > &model, DataTpl< Scalar, Options, JointCollectionTpl > &data)
Updates the position of each frame contained in the model.
pinocchio::EmptyForwardStepBinaryVisitNoData::algo
static EIGEN_DONT_INLINE void algo(const JointModelBase< JointModel1 > &, const JointModelBase< JointModel2 > &)
Definition: timings.cpp:141
filename
filename
pinocchio::jacobianCenterOfMass
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...
pinocchio::EmptyForwardStepUnaryVisit::ArgsType
fusion::NoArg ArgsType
Definition: timings.cpp:36
urdf.hpp
data.hpp
pinocchio::ccrba
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...
pinocchio::EmptyForwardStepBinaryVisit::algo
static EIGEN_DONT_INLINE void algo(const JointModelBase< JointModel1 > &, const JointModelBase< JointModel2 > &, JointDataBase< typename JointModel1::JointDataDerived > &, JointDataBase< typename JointModel2::JointDataDerived > &)
Definition: timings.cpp:104
pinocchio::urdf::buildModel
ModelTpl< Scalar, Options, JointCollectionTpl > & buildModel(const std::string &filename, const typename ModelTpl< Scalar, Options, JointCollectionTpl >::JointModel &rootJoint, const std::string &rootJointName, 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...
pinocchio::nonLinearEffects
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),...
pinocchio::framesForwardKinematics
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....
PinocchioTicToc::US
@ US
Definition: timer.hpp:53
cholesky.hpp
main
int main(int argc, const char **argv)
Definition: timings.cpp:164
pinocchio::EmptyForwardStepUnaryVisitNoData::ArgsType
fusion::NoArg ArgsType
Definition: timings.cpp:69
pinocchio::cholesky::decompose
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.
pinocchio::emptyForwardPassUnaryVisitNoData
void emptyForwardPassUnaryVisitNoData(const ModelTpl< Scalar, Options, JointCollectionTpl > &model, DataTpl< Scalar, Options, JointCollectionTpl > &data)
Definition: timings.cpp:78
pinocchio::EmptyForwardStepBinaryVisit::Model
ModelTpl< Scalar, Options, JointCollectionTpl > Model
Definition: timings.cpp:98
centroidal.hpp
pinocchio::rnea
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...
pinocchio::emptyForwardPassBinaryVisit
void emptyForwardPassBinaryVisit(const ModelTpl< Scalar, Options, JointCollectionTpl > &model, DataTpl< Scalar, Options, JointCollectionTpl > &data)
Definition: timings.cpp:114
pinocchio::fusion::NoArg
boost::blank NoArg
Definition: fusion.hpp:20
pinocchio::emptyForwardPassBinaryVisitNoData
void emptyForwardPassBinaryVisitNoData(const ModelTpl< Scalar, Options, JointCollectionTpl > &model, DataTpl< Scalar, Options, JointCollectionTpl > &data)
Definition: timings.cpp:147
pinocchio::EmptyForwardStepUnaryVisit::algo
static void algo(const JointModelBase< JointModel > &, JointDataBase< typename JointModel::JointDataDerived > &)
Definition: timings.cpp:40
pinocchio::JointIndex
Index JointIndex
Definition: multibody/fwd.hpp:26
PINOCCHIO_ALIGNED_STD_VECTOR
#define PINOCCHIO_ALIGNED_STD_VECTOR(Type)
Definition: container/aligned-vector.hpp:11
pinocchio::EmptyForwardStepBinaryVisitNoData::Data
DataTpl< Scalar, Options, JointCollectionTpl > Data
Definition: timings.cpp:135
pinocchio::EmptyForwardStepUnaryVisit
Definition: timings.cpp:30
sample-models.hpp
jacobian.hpp
pinocchio::ModelTpl
Definition: context/generic.hpp:20
pinocchio::computeCoriolisMatrix
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:
pinocchio::EmptyForwardStepUnaryVisitNoData
Definition: timings.cpp:62
crba.hpp
pinocchio::computeAllTerms
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...
PinocchioTicToc
Definition: timer.hpp:47
meshcat-viewer.qs
qs
Definition: meshcat-viewer.py:128
pinocchio::EmptyForwardStepUnaryVisit::Model
ModelTpl< Scalar, Options, JointCollectionTpl > Model
Definition: timings.cpp:33
pinocchio::model
JointCollectionTpl & model
Definition: joint-configuration.hpp:1082
pinocchio
Main pinocchio namespace.
Definition: timings.cpp:27
PINOCCHIO_UNUSED_VARIABLE
#define PINOCCHIO_UNUSED_VARIABLE(var)
Helper to declare that a parameter is unused.
Definition: include/pinocchio/macros.hpp:72
PINOCCHIO_MODEL_DIR
#define PINOCCHIO_MODEL_DIR
Definition: build-reduced-model.cpp:11
pinocchio::centerOfMass
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....
PinocchioTicToc::tic
void tic()
Definition: timer.hpp:82
pinocchio::EmptyForwardStepUnaryVisitNoData::algo
static EIGEN_DONT_INLINE void algo(const JointModelBase< JointModel > &)
Definition: timings.cpp:72
pinocchio::LOCAL
@ LOCAL
Definition: multibody/fwd.hpp:50


pinocchio
Author(s):
autogenerated on Sun Nov 10 2024 03:43:02