timings-cppad-jit.cpp
Go to the documentation of this file.
1 //
2 // Copyright (c) 2022 INRIA
3 //
7 
10 
16 
18 
19 #include <iostream>
20 
21 #ifdef _WIN32
22  #define DLL_EXT ".dll"
23 #else
24  #define DLL_EXT ".so"
25 #endif
26 
28 
30 
31 int main()
32 {
33  using namespace Eigen;
34  using namespace pinocchio;
35 
37 #ifdef NDEBUG
38  const int NBT = 1000 * 100;
39 #else
40  const int NBT = 1;
41  std::cout << "(the time score in debug mode is not relevant) " << std::endl;
42 #endif
43 
44  using CppAD::AD;
45  using CppAD::NearEqual;
46 
47  enum
48  {
49  Options = 0
50  };
51  typedef double Scalar;
52  typedef AD<Scalar> ADScalar;
53  typedef CppAD::cg::CG<Scalar> CGScalar;
54  typedef CppAD::AD<CGScalar> ADCGScalar;
55  typedef CppAD::ADFun<CGScalar> ADCGFun;
56 
57  typedef Eigen::Matrix<ADScalar, Eigen::Dynamic, 1> ADVectorXs;
58  typedef Eigen::Matrix<ADCGScalar, Eigen::Dynamic, 1, Options> ADCGVectorXs;
59  typedef Eigen::Matrix<ADScalar, Eigen::Dynamic, Eigen::Dynamic> ADMatrixXs;
60  typedef Eigen::Matrix<Scalar, Eigen::Dynamic, Eigen::Dynamic, Eigen::RowMajor> RowMatrixXs;
61 
63  typedef Model::Data Data;
64 
65  typedef pinocchio::ModelTpl<ADScalar> ADModel;
66  typedef ADModel::Data ADData;
67 
68  typedef pinocchio::ModelTpl<ADCGScalar> ADCGModel;
69  typedef ADCGModel::Data ADCGData;
70 
71  typedef Model::ConfigVectorType ConfigVectorType;
72  typedef Model::TangentVectorType TangentVectorType;
73 
74  typedef ADModel::ConfigVectorType ADConfigVectorType;
75  typedef ADModel::TangentVectorType ADTangentVectorType;
76 
77  typedef ADCGModel::ConfigVectorType ADCGConfigVectorType;
78  typedef ADCGModel::TangentVectorType ADCGTangentVectorType;
79 
80  Model model;
82  int nq = model.nq;
83  int nv = model.nv;
84  int nx = nq + 2 * nv;
85  model.lowerPositionLimit.head<3>().fill(-1.);
86  model.upperPositionLimit.head<3>().fill(1.);
87 
88  ConfigVectorType q(nq);
90  TangentVectorType v(TangentVectorType::Random(nv));
91  TangentVectorType a(TangentVectorType::Random(nv));
92 
93  {
94  Data data(model);
95 
96  std::vector<ConfigVectorType> qs;
97  for (size_t it = 0; it < NBT; ++it)
98  {
100  qs.push_back(q);
101  }
102 
103  timer.tic();
104  SMOOTH(NBT)
105  {
107  data.M.triangularView<Eigen::StrictlyLower>() =
108  data.M.transpose().triangularView<Eigen::StrictlyLower>();
109  }
110  std::cout << "Calculate data.M (JSIM) with crba = \t\t";
111  timer.toc(std::cout, NBT);
112  }
113 
114  {
115  ADModel ad_model = model.cast<ADScalar>();
116  ADData ad_data(ad_model);
117 
118  ADConfigVectorType ad_q = q.cast<ADScalar>();
119 
120  CppAD::Independent(ad_q);
121  pinocchio::crba(ad_model, ad_data, ad_q, pinocchio::Convention::WORLD);
122  ad_data.M.triangularView<Eigen::StrictlyLower>() =
123  ad_data.M.transpose().triangularView<Eigen::StrictlyLower>();
124 
125  ADVectorXs M_vector =
126  Eigen::Map<ADVectorXs>(ad_data.M.data(), ad_data.M.cols() * ad_data.M.rows());
127 
128  CppAD::ADFun<Scalar> ad_fun(ad_q, M_vector);
129  ad_fun.function_name_set("ad_fun_crba");
130 
131  // create csrc_file
132  std::string c_type = "double";
133  std::string csrc_file = "./jit_JSIM_crba.c";
134  std::ofstream ofs;
135  ofs.open(csrc_file, std::ofstream::out);
136  ad_fun.to_csrc(ofs, c_type);
137  ofs.close();
138 
139  // create dll_file
140  std::string dll_file = "./jit_JSIM_crba" DLL_EXT;
141  CPPAD_TESTVECTOR(std::string) csrc_files(1);
142  csrc_files[0] = csrc_file;
143  std::map<std::string, std::string> options;
144  std::string err_msg = CppAD::create_dll_lib(dll_file, csrc_files, options);
145  if (err_msg != "")
146  {
147  std::cerr << "jit_JSIM_crba: err_msg = " << err_msg << "\n";
148  }
149 
150  // dll_linker
151  CppAD::link_dll_lib dll_linker(dll_file, err_msg);
152  if (err_msg != "")
153  {
154  std::cerr << "jit_JSIM_crba: err_msg = " << err_msg << "\n";
155  }
156 
157  std::string function_name = "cppad_jit_ad_fun_crba";
158  void * void_ptr = dll_linker(function_name, err_msg);
159  if (err_msg != "")
160  {
161  std::cerr << "jit_JSIM_crba: err_msg = " << err_msg << "\n";
162  }
163 
164  using CppAD::jit_double;
165  jit_double ad_fun_ptr = reinterpret_cast<jit_double>(void_ptr);
166 
167  CPPAD_TESTVECTOR(Scalar) x((size_t)nq);
168  size_t compare_change = 0, nx = (size_t)nq, nM_vector = (size_t)nv * (size_t)nv;
169  CPPAD_TESTVECTOR(Scalar) M_vector_jit(nM_vector);
170 
171  std::vector<CPPAD_TESTVECTOR(Scalar)> xs;
172  for (size_t it = 0; it < NBT; ++it)
173  {
175  Eigen::Map<Data::ConfigVectorType>(x.data(), nq, 1) = q;
176  xs.push_back(x);
177  }
178 
179  timer.tic();
180  SMOOTH(NBT)
181  {
182  ad_fun_ptr(nx, xs[_smooth].data(), nM_vector, M_vector_jit.data(), &compare_change);
183  }
184  std::cout << "Calculate data.M (JSIM) with crba using cppad-jit = \t\t";
185  timer.toc(std::cout, NBT);
186  }
187 
188  {
189  ADCGModel ad_model(model.template cast<ADCGScalar>());
190  ADCGData ad_data(ad_model);
191 
192  ADCGConfigVectorType ad_q = q.cast<ADCGScalar>();
193  ad_q = q.cast<ADCGScalar>();
194 
195  std::unique_ptr<CppAD::cg::ModelCSourceGen<Scalar>> cgen_ptr;
196  std::unique_ptr<CppAD::cg::ModelLibraryCSourceGen<Scalar>> libcgen_ptr;
197  std::unique_ptr<CppAD::cg::DynamicModelLibraryProcessor<Scalar>> dynamicLibManager_ptr;
198  std::unique_ptr<CppAD::cg::DynamicLib<Scalar>> dynamicLib_ptr;
199  std::unique_ptr<CppAD::cg::GenericModel<Scalar>> generatedFun_ptr;
200 
201  const std::string & function_name = "crba";
202  const std::string & library_name = "cg_crba_eval";
203  const std::string & compile_options = "-Ofast";
204 
205  CppAD::Independent(ad_q);
206  pinocchio::crba(ad_model, ad_data, ad_q, pinocchio::Convention::WORLD);
207  ad_data.M.triangularView<Eigen::StrictlyLower>() =
208  ad_data.M.transpose().triangularView<Eigen::StrictlyLower>();
209 
210  ADCGVectorXs M_vector =
211  Eigen::Map<ADCGVectorXs>(ad_data.M.data(), ad_data.M.cols() * ad_data.M.rows());
212 
213  ADCGFun ad_fun;
214  ad_fun.Dependent(ad_q, M_vector);
215  ad_fun.optimize("no_compare_op");
216 
217  // generates source code
218  cgen_ptr = std::unique_ptr<CppAD::cg::ModelCSourceGen<Scalar>>(
219  new CppAD::cg::ModelCSourceGen<Scalar>(ad_fun, function_name));
220  cgen_ptr->setCreateForwardZero(true);
221  cgen_ptr->setCreateJacobian(false);
222  libcgen_ptr = std::unique_ptr<CppAD::cg::ModelLibraryCSourceGen<Scalar>>(
223  new CppAD::cg::ModelLibraryCSourceGen<Scalar>(*cgen_ptr));
224 
225  dynamicLibManager_ptr = std::unique_ptr<CppAD::cg::DynamicModelLibraryProcessor<Scalar>>(
226  new CppAD::cg::DynamicModelLibraryProcessor<Scalar>(*libcgen_ptr, library_name));
227 
228  CppAD::cg::GccCompiler<Scalar> compiler(PINOCCHIO_CXX_COMPILER);
229  std::vector<std::string> compile_flags = compiler.getCompileFlags();
230  compile_flags[0] = compile_options;
231  compiler.setCompileFlags(compile_flags);
232  dynamicLibManager_ptr->createDynamicLibrary(compiler, false);
233 
234  const auto it = dynamicLibManager_ptr->getOptions().find("dlOpenMode");
235  if (it == dynamicLibManager_ptr->getOptions().end())
236  {
237  dynamicLib_ptr.reset(new CppAD::cg::LinuxDynamicLib<Scalar>(
238  dynamicLibManager_ptr->getLibraryName()
239  + CppAD::cg::system::SystemInfo<>::DYNAMIC_LIB_EXTENSION));
240  }
241  else
242  {
243  int dlOpenMode = std::stoi(it->second);
244  dynamicLib_ptr.reset(new CppAD::cg::LinuxDynamicLib<Scalar>(
245  dynamicLibManager_ptr->getLibraryName()
246  + CppAD::cg::system::SystemInfo<>::DYNAMIC_LIB_EXTENSION,
247  dlOpenMode));
248  }
249 
250  generatedFun_ptr = dynamicLib_ptr->model(function_name.c_str());
251 
252  CPPAD_TESTVECTOR(Scalar) x((size_t)nq);
253  CPPAD_TESTVECTOR(Scalar) y((size_t)nv * (size_t)nv);
254 
255  std::vector<CPPAD_TESTVECTOR(Scalar)> xs;
256  for (size_t it = 0; it < NBT; ++it)
257  {
259  Eigen::Map<Data::ConfigVectorType>(x.data(), nq, 1) = q;
260  xs.push_back(x);
261  }
262 
263  timer.tic();
264  SMOOTH(NBT)
265  {
266  generatedFun_ptr->ForwardZero(xs[_smooth], y);
267  }
268  std::cout << "Calculate data.M (JSIM) with crba using cppadcg = \t\t";
269  timer.toc(std::cout, NBT);
270  }
271 
272  {
273  Data data(model);
274 
275  std::vector<ConfigVectorType> qs, vs, as;
276  for (size_t it = 0; it < NBT; ++it)
277  {
279  TangentVectorType v(TangentVectorType::Random(nv));
280  TangentVectorType a(TangentVectorType::Random(nv));
281  qs.push_back(q);
282  vs.push_back(v);
283  as.push_back(a);
284  }
285 
286  timer.tic();
287  SMOOTH(NBT)
288  {
289  computeRNEADerivatives(model, data, qs[_smooth], vs[_smooth], as[_smooth]);
290  }
291  std::cout << "Calculate dtau_dx using computeRNEADerivatives = \t\t";
292  timer.toc(std::cout, NBT);
293  }
294 
295  {
296  ADModel ad_model = model.cast<ADScalar>();
297  ADData ad_data(ad_model);
298 
299  ADConfigVectorType ad_q = q.cast<ADScalar>();
300  ADTangentVectorType ad_v = v.cast<ADScalar>();
301  ADTangentVectorType ad_a = a.cast<ADScalar>();
302  ADConfigVectorType ad_X = ADConfigVectorType::Zero(nx);
303  Eigen::DenseIndex i = 0;
304  ad_X.segment(i, nq) = ad_q;
305  i += nq;
306  ad_X.segment(i, nv) = ad_v;
307  i += nv;
308  ad_X.segment(i, nv) = ad_a;
309  i += nv;
310 
311  CppAD::Independent(ad_X);
313  ad_model, ad_data, ad_X.segment(0, nq), ad_X.segment(nq, nv), ad_X.segment(nq + nv, nv));
314 
315  ADVectorXs ad_Y(nv);
316  Eigen::Map<ADData::TangentVectorType>(ad_Y.data(), nv, 1) = ad_data.tau;
317 
318  CppAD::ADFun<Scalar> f(ad_X, ad_Y);
319  CppAD::ADFun<ADScalar, Scalar> af = f.base2ad();
320 
321  CppAD::Independent(ad_X);
322  ADMatrixXs dtau_dx = af.Jacobian(ad_X);
323  ADVectorXs dtau_dx_vector(nv * nx);
324  dtau_dx_vector = Eigen::Map<ADVectorXs>(dtau_dx.data(), dtau_dx.cols() * dtau_dx.rows());
325  CppAD::ADFun<double> ad_fun(ad_X, dtau_dx_vector);
326 
327  ad_fun.function_name_set("ad_fun");
328 
329  // create csrc_file
330  std::string c_type = "double";
331  std::string csrc_file = "./jit_JSIM.c";
332  std::ofstream ofs;
333  ofs.open(csrc_file, std::ofstream::out);
334  ad_fun.to_csrc(ofs, c_type);
335  ofs.close();
336 
337  // create dll_file
338  std::string dll_file = "./jit_JSIM" DLL_EXT;
339  CPPAD_TESTVECTOR(std::string) csrc_files(1);
340  csrc_files[0] = csrc_file;
341  std::map<std::string, std::string> options;
342  std::string err_msg = CppAD::create_dll_lib(dll_file, csrc_files, options);
343  if (err_msg != "")
344  {
345  std::cerr << "jit_JSIM: err_msg = " << err_msg << "\n";
346  }
347 
348  // dll_linker
349  CppAD::link_dll_lib dll_linker(dll_file, err_msg);
350  if (err_msg != "")
351  {
352  std::cerr << "jit_JSIM: err_msg = " << err_msg << "\n";
353  }
354 
355  std::string function_name = "cppad_jit_ad_fun";
356  void * void_ptr = dll_linker(function_name, err_msg);
357  if (err_msg != "")
358  {
359  std::cerr << "jit_JSIM: err_msg = " << err_msg << "\n";
360  }
361 
362  using CppAD::jit_double;
363  jit_double ad_fun_ptr = reinterpret_cast<jit_double>(void_ptr);
364 
365  CPPAD_TESTVECTOR(Scalar) x((size_t)nx);
366  std::vector<CPPAD_TESTVECTOR(Scalar)> xs;
367  for (size_t it = 0; it < NBT; ++it)
368  {
370  TangentVectorType v(TangentVectorType::Random(nv));
371  TangentVectorType a(TangentVectorType::Random(nv));
372  ConfigVectorType _x = ConfigVectorType::Zero(nx);
373  Eigen::DenseIndex i = 0;
374  _x.segment(i, nq) = q;
375  i += nq;
376  _x.segment(i, nv) = v;
377  i += nv;
378  _x.segment(i, nv) = a;
379  i += nv;
380 
381  Eigen::Map<Data::TangentVectorType>(x.data(), nx, 1) = _x;
382  xs.push_back(x);
383  }
384 
385  size_t compare_change = 0, nx_ = (size_t)nx, ndtau_dx = (size_t)nv * (size_t)nx;
386  std::vector<double> dtau_dx_jit(ndtau_dx);
387 
388  timer.tic();
389  SMOOTH(NBT)
390  {
391  ad_fun_ptr(nx_, xs[_smooth].data(), ndtau_dx, dtau_dx_jit.data(), &compare_change);
392  }
393  std::cout << "Calculate dtau_dx (rnea) with cppad using jit = \t\t";
394  timer.toc(std::cout, NBT);
395  }
396 
397  {
398  ADModel ad_model = model.cast<ADScalar>();
399  ADData ad_data(ad_model);
400 
401  ADConfigVectorType ad_q = q.cast<ADScalar>();
402  ADTangentVectorType ad_v = v.cast<ADScalar>();
403  ADTangentVectorType ad_a = a.cast<ADScalar>();
404 
405  ADConfigVectorType ad_X = ADConfigVectorType::Zero(nq + 2 * nv);
406  Eigen::DenseIndex i = 0;
407  ad_X.segment(i, nq) = ad_q;
408  i += nq;
409  ad_X.segment(i, nv) = ad_v;
410  i += nv;
411  ad_X.segment(i, nv) = ad_a;
412  i += nv;
413 
414  CppAD::Independent(ad_X);
416  ad_model, ad_data, ad_X.segment(0, nq), ad_X.segment(nq, nv), ad_X.segment(nq + nv, nv));
417 
418  ADVectorXs ad_Y(nv);
419  Eigen::Map<ADData::TangentVectorType>(ad_Y.data(), nv, 1) = ad_data.tau;
420 
421  CppAD::ADFun<Scalar> ad_fun(ad_X, ad_Y);
422 
423  CPPAD_TESTVECTOR(Scalar) x((size_t)nx);
424  std::vector<CPPAD_TESTVECTOR(Scalar)> xs;
425  for (size_t it = 0; it < NBT; ++it)
426  {
428  TangentVectorType v(TangentVectorType::Random(nv));
429  TangentVectorType a(TangentVectorType::Random(nv));
430  ConfigVectorType _x = ConfigVectorType::Zero(nq + 2 * nv);
431  Eigen::DenseIndex i = 0;
432  _x.segment(i, nq) = q;
433  i += nq;
434  _x.segment(i, nv) = v;
435  i += nv;
436  _x.segment(i, nv) = a;
437  i += nv;
438 
439  Eigen::Map<Data::TangentVectorType>(x.data(), nx, 1) = _x;
440  xs.push_back(x);
441  }
442  timer.tic();
443  SMOOTH(NBT)
444  {
445  CPPAD_TESTVECTOR(Scalar) dtau_da = ad_fun.Jacobian(xs[_smooth]);
446  }
447  std::cout << "Calculate dtau_dx (rnea) with cppad = \t\t";
448  timer.toc(std::cout, NBT);
449  }
450 
451  {
452  ADCGModel ad_model(model.template cast<ADCGScalar>());
453  ADCGData ad_data(ad_model);
454 
455  ADCGVectorXs ad_Y(nv);
456 
457  ADCGConfigVectorType ad_q = q.cast<ADCGScalar>();
458  ADCGTangentVectorType ad_v = v.cast<ADCGScalar>();
459  ADCGTangentVectorType ad_a = a.cast<ADCGScalar>();
460  ADCGConfigVectorType ad_X = ADCGConfigVectorType::Zero(nx);
461  Eigen::DenseIndex i = 0;
462  ad_X.segment(i, nq) = ad_q;
463  i += nq;
464  ad_X.segment(i, nv) = ad_v;
465  i += nv;
466  ad_X.segment(i, nv) = ad_a;
467  i += nv;
468 
469  ADCGFun ad_fun;
470 
471  std::unique_ptr<CppAD::cg::ModelCSourceGen<Scalar>> cgen_ptr;
472  std::unique_ptr<CppAD::cg::ModelLibraryCSourceGen<Scalar>> libcgen_ptr;
473  std::unique_ptr<CppAD::cg::DynamicModelLibraryProcessor<Scalar>> dynamicLibManager_ptr;
474  std::unique_ptr<CppAD::cg::DynamicLib<Scalar>> dynamicLib_ptr;
475  std::unique_ptr<CppAD::cg::GenericModel<Scalar>> generatedFun_ptr;
476 
477  const std::string & function_name = "rnea";
478  const std::string & library_name = "cg_rnea_eval";
479  const std::string & compile_options = "-Ofast";
480 
481  CppAD::Independent(ad_X);
483  ad_model, ad_data, ad_X.segment(0, nq), ad_X.segment(nq, nv), ad_X.segment(nq + nv, nv));
484  ad_Y = ad_data.tau;
485  ad_fun.Dependent(ad_X, ad_Y);
486  ad_fun.optimize("no_compare_op");
487  RowMatrixXs jac = RowMatrixXs::Zero(ad_Y.size(), ad_X.size());
488 
489  // generates source code
490  cgen_ptr = std::unique_ptr<CppAD::cg::ModelCSourceGen<Scalar>>(
491  new CppAD::cg::ModelCSourceGen<Scalar>(ad_fun, function_name));
492  cgen_ptr->setCreateForwardZero(true);
493  cgen_ptr->setCreateJacobian(true);
494  libcgen_ptr = std::unique_ptr<CppAD::cg::ModelLibraryCSourceGen<Scalar>>(
495  new CppAD::cg::ModelLibraryCSourceGen<Scalar>(*cgen_ptr));
496 
497  dynamicLibManager_ptr = std::unique_ptr<CppAD::cg::DynamicModelLibraryProcessor<Scalar>>(
498  new CppAD::cg::DynamicModelLibraryProcessor<Scalar>(*libcgen_ptr, library_name));
499 
500  CppAD::cg::GccCompiler<Scalar> compiler(PINOCCHIO_CXX_COMPILER);
501  std::vector<std::string> compile_flags = compiler.getCompileFlags();
502  compile_flags[0] = compile_options;
503  compiler.setCompileFlags(compile_flags);
504  dynamicLibManager_ptr->createDynamicLibrary(compiler, false);
505 
506  const auto it = dynamicLibManager_ptr->getOptions().find("dlOpenMode");
507  if (it == dynamicLibManager_ptr->getOptions().end())
508  {
509  dynamicLib_ptr.reset(new CppAD::cg::LinuxDynamicLib<Scalar>(
510  dynamicLibManager_ptr->getLibraryName()
511  + CppAD::cg::system::SystemInfo<>::DYNAMIC_LIB_EXTENSION));
512  }
513  else
514  {
515  int dlOpenMode = std::stoi(it->second);
516  dynamicLib_ptr.reset(new CppAD::cg::LinuxDynamicLib<Scalar>(
517  dynamicLibManager_ptr->getLibraryName()
518  + CppAD::cg::system::SystemInfo<>::DYNAMIC_LIB_EXTENSION,
519  dlOpenMode));
520  }
521 
522  generatedFun_ptr = dynamicLib_ptr->model(function_name.c_str());
523 
524  CPPAD_TESTVECTOR(Scalar) x((size_t)nv);
525  std::vector<size_t> xs;
526  for (size_t it = 0; it < NBT; ++it)
527  {
528  ConfigVectorType q = pinocchio::randomConfiguration(model);
529  TangentVectorType v(TangentVectorType::Random(nv));
530  TangentVectorType a(TangentVectorType::Random(nv));
531 
532  ConfigVectorType x = ConfigVectorType::Zero(nq + 2 * nv);
533  i = 0;
534  x.segment(i, nq) = q;
535  i += nq;
536  x.segment(i, nv) = v;
537  i += nv;
538  x.segment(i, nv) = a;
539  i += nv;
540 
541  xs.push_back(static_cast<size_t>(x.size()));
542  }
543 
544  CppAD::cg::ArrayView<Scalar> jac_(jac.data(), (size_t)jac.size());
545 
546  timer.tic();
547  SMOOTH(NBT)
548  {
549  generatedFun_ptr->Jacobian(CppAD::cg::ArrayView<const Scalar>(x.data(), xs[_smooth]), jac_);
550  }
551  std::cout << "Calculate dtau_dx (rnea) with cppad code gen = \t\t";
552  timer.toc(std::cout, NBT);
553  }
554 
556  {
557  std::remove("cg_rnea_eval.dylib");
558  std::remove("jit_JSIM.c");
559  std::remove("jit_JSIM.so");
560  std::remove("jit_JSIM_crba.c");
561  std::remove("jit_JSIM_crba.so");
562  }
563 
564  std::cout << "--" << std::endl;
565  return 0;
566 }
PinocchioTicToc::toc
double toc()
Definition: timer.hpp:88
Eigen
pinocchio::DataTpl
Definition: context/generic.hpp:25
autodiff-rnea.nq
nq
Definition: autodiff-rnea.py:11
cppadcg.hpp
autodiff-rnea.nv
nv
Definition: autodiff-rnea.py:12
codegen-rnea.jac
jac
Definition: codegen-rnea.py:43
aligned-vector.hpp
y
y
pinocchio::Convention::WORLD
@ WORLD
inverse-kinematics.i
int i
Definition: inverse-kinematics.py:20
code-generator-algo.hpp
kinematics.hpp
model.hpp
setup.data
data
Definition: cmake/cython/setup.in.py:48
pinocchio::python::Scalar
context::Scalar Scalar
Definition: admm-solver.cpp:29
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::python::computeRNEADerivatives
bp::tuple computeRNEADerivatives(const context::Model &model, context::Data &data, const context::VectorXs &q, const context::VectorXs &v, const context::VectorXs &a)
Definition: expose-rnea-derivatives.cpp:38
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::python::context::Model
ModelTpl< Scalar, Options > Model
Definition: bindings/python/context/generic.hpp:61
autodiff-rnea.f
f
Definition: autodiff-rnea.py:24
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:325
main
int main()
Definition: timings-cppad-jit.cpp:31
rnea.hpp
timer.hpp
pinocchio::context::RowMatrixXs
Eigen::Matrix< Scalar, Eigen::Dynamic, Eigen::Dynamic, Eigen::RowMajor|Options > RowMatrixXs
Definition: context/generic.hpp:51
collision-with-point-clouds.nx
int nx
Definition: collision-with-point-clouds.py:38
anymal-simulation.model
model
Definition: anymal-simulation.py:12
pinocchio::python::Options
@ Options
Definition: expose-contact-inverse-dynamics.cpp:22
SMOOTH
#define SMOOTH(s)
Definition: timer.hpp:38
joint-configuration.hpp
pinocchio::python::context::Data
DataTpl< Scalar, Options > Data
Definition: bindings/python/context/generic.hpp:62
autodiff-rnea.v
v
Definition: autodiff-rnea.py:15
DLL_EXT
#define DLL_EXT
Definition: timings-cppad-jit.cpp:24
pinocchio::ModelTpl::TangentVectorType
VectorXs TangentVectorType
Dense vectorized version of a joint tangent vector (e.g. velocity, acceleration, etc)....
Definition: multibody/model.hpp:96
data.hpp
x
x
q
q
autodiff-rnea.dtau_da
dtau_da
Definition: autodiff-rnea.py:29
a
Vec3f a
PinocchioTicToc::US
@ US
Definition: timer.hpp:53
fill
fill
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...
DELETE_GENERATED_LIBS_AFTER_TEST
bool DELETE_GENERATED_LIBS_AFTER_TEST
Definition: timings-cppad-jit.cpp:29
pinocchio::ModelTpl::ConfigVectorType
VectorXs ConfigVectorType
Dense vectorized version of a joint configuration vector.
Definition: multibody/model.hpp:88
sample-models.hpp
jacobian.hpp
pinocchio::ModelTpl
Definition: context/generic.hpp:20
crba.hpp
PinocchioTicToc
Definition: timer.hpp:47
meshcat-viewer.qs
qs
Definition: meshcat-viewer.py:127
pinocchio
Main pinocchio namespace.
Definition: timings.cpp:27
PinocchioTicToc::tic
void tic()
Definition: timer.hpp:82


pinocchio
Author(s):
autogenerated on Tue Jun 25 2024 02:42:41