timings-cg.cpp
Go to the documentation of this file.
1 //
2 // Copyright (c) 2018 CNRS
3 //
4 
6 
23 
25 
26 #include <iostream>
27 
29 
30 int main(int argc, const char ** argv)
31 {
32  using namespace Eigen;
33  using namespace pinocchio;
34 
36 #ifdef NDEBUG
37  const int NBT = 1000 * 100;
38 #else
39  const int NBT = 1;
40  std::cout << "(the time score in debug mode is not relevant) " << std::endl;
41 #endif
42 
44  std::string filename = PINOCCHIO_MODEL_DIR + std::string("/simple_humanoid.urdf");
45  if (argc > 1)
46  filename = argv[1];
47 
48  bool with_ff = true;
49  if (argc > 2)
50  {
51  const std::string ff_option = argv[2];
52  if (ff_option == "-no-ff")
53  with_ff = false;
54  }
55 
56  if (filename == "H")
58  else if (with_ff)
60  else
62 
63  std::cout << "nq = " << model.nq << std::endl;
64  std::cout << "nv = " << model.nv << std::endl;
65  std::cout << "--" << std::endl;
66 
68 
69  const std::string RF = "RLEG_ANKLE_R";
70  const std::string LF = "LLEG_ANKLE_R";
72 
73  RigidConstraintModel ci_RF(CONTACT_6D, model, model.getFrameId(RF), WORLD);
74  RigidConstraintModel ci_LF(CONTACT_6D, model, model.getFrameId(LF), WORLD);
75  contact_models_6D6D.push_back(ci_RF);
76  contact_models_6D6D.push_back(ci_LF);
77 
79 
80  RigidConstraintData cd_RF(ci_RF);
81  contact_datas_6D6D.push_back(cd_RF);
82  RigidConstraintData cd_LF(ci_LF);
83  contact_datas_6D6D.push_back(cd_LF);
84 
85  VectorXd qmax = Eigen::VectorXd::Ones(model.nq);
86 
87  CodeGenRNEA<double> rnea_code_gen(model);
88  rnea_code_gen.initLib();
89  rnea_code_gen.loadLib();
90 
91  CodeGenABA<double> aba_code_gen(model);
92  aba_code_gen.initLib();
93  aba_code_gen.loadLib();
94 
95  CodeGenCRBA<double> crba_code_gen(model);
96  crba_code_gen.initLib();
97  crba_code_gen.loadLib();
98 
99  CodeGenMinv<double> minv_code_gen(model);
100  minv_code_gen.initLib();
101  minv_code_gen.loadLib();
102 
103  CodeGenRNEADerivatives<double> rnea_derivatives_code_gen(model);
104  rnea_derivatives_code_gen.initLib();
105  rnea_derivatives_code_gen.loadLib();
106 
107  CodeGenABADerivatives<double> aba_derivatives_code_gen(model);
108  aba_derivatives_code_gen.initLib();
109  aba_derivatives_code_gen.loadLib();
110 
111  CodeGenConstraintDynamicsDerivatives<double> constraint_dynamics_derivatives_code_gen(
112  model, contact_models_6D6D);
113  constraint_dynamics_derivatives_code_gen.initLib();
114  constraint_dynamics_derivatives_code_gen.loadLib();
115 
120 
121  for (size_t i = 0; i < NBT; ++i)
122  {
123  qs[i] = randomConfiguration(model, -qmax, qmax);
124  qdots[i] = Eigen::VectorXd::Random(model.nv);
125  qddots[i] = Eigen::VectorXd::Random(model.nv);
126  taus[i] = Eigen::VectorXd::Random(model.nv);
127  }
128 
129  timer.tic();
130  SMOOTH(NBT)
131  {
132  rnea(model, data, qs[_smooth], qdots[_smooth], qddots[_smooth]);
133  }
134  std::cout << "RNEA = \t\t";
135  timer.toc(std::cout, NBT);
136 
137  timer.tic();
138  SMOOTH(NBT)
139  {
140  rnea_code_gen.evalFunction(qs[_smooth], qdots[_smooth], qddots[_smooth]);
141  }
142  std::cout << "RNEA generated = \t\t";
143  timer.toc(std::cout, NBT);
144 
145  timer.tic();
146  SMOOTH(NBT)
147  {
148  rnea_code_gen.evalJacobian(qs[_smooth], qdots[_smooth], qddots[_smooth]);
149  }
150  std::cout << "RNEA partial derivatives auto diff + code gen = \t\t";
151  timer.toc(std::cout, NBT);
152 
153  timer.tic();
154  SMOOTH(NBT)
155  {
156  rnea_derivatives_code_gen.evalFunction(qs[_smooth], qdots[_smooth], qddots[_smooth]);
157  }
158  std::cout << "RNEA partial derivatives code gen = \t\t";
159  timer.toc(std::cout, NBT);
160 
161  timer.tic();
162  SMOOTH(NBT)
163  {
164  aba(model, data, qs[_smooth], qdots[_smooth], taus[_smooth], Convention::WORLD);
165  }
166  timer.toc();
167 
168  timer.tic();
169  SMOOTH(NBT)
170  {
171  crba(model, data, qs[_smooth], Convention::WORLD);
172  }
173  std::cout << "CRBA = \t\t";
174  timer.toc(std::cout, NBT);
175 
176  timer.tic();
177  SMOOTH(NBT)
178  {
179  crba_code_gen.evalFunction(qs[_smooth]);
180  }
181  std::cout << "CRBA generated = \t\t";
182  timer.toc(std::cout, NBT);
183 
184  timer.tic();
185  SMOOTH(NBT)
186  {
187  computeMinverse(model, data, qs[_smooth]);
188  }
189  std::cout << "Minv = \t\t";
190  timer.toc(std::cout, NBT);
191 
192  timer.tic();
193  SMOOTH(NBT)
194  {
195  minv_code_gen.evalFunction(qs[_smooth]);
196  }
197  std::cout << "Minv generated = \t\t";
198  timer.toc(std::cout, NBT);
199 
200  timer.tic();
201  SMOOTH(NBT)
202  {
203  aba(model, data, qs[_smooth], qdots[_smooth], taus[_smooth], Convention::WORLD);
204  }
205  std::cout << "ABA = \t\t";
206  timer.toc(std::cout, NBT);
207 
208  timer.tic();
209  SMOOTH(NBT)
210  {
211  aba_code_gen.evalFunction(qs[_smooth], qdots[_smooth], taus[_smooth]);
212  }
213  std::cout << "ABA generated = \t\t";
214  timer.toc(std::cout, NBT);
215 
216  timer.tic();
217  SMOOTH(NBT)
218  {
219  aba_code_gen.evalJacobian(qs[_smooth], qdots[_smooth], taus[_smooth]);
220  }
221  std::cout << "ABA partial derivatives auto diff + code gen = \t\t";
222  timer.toc(std::cout, NBT);
223 
224  timer.tic();
225  SMOOTH(NBT)
226  {
227  aba_derivatives_code_gen.evalFunction(qs[_smooth], qdots[_smooth], qddots[_smooth]);
228  }
229  std::cout << "ABA partial derivatives code gen = \t\t";
230  timer.toc(std::cout, NBT);
231 
232  pinocchio::initConstraintDynamics(model, data, contact_models_6D6D);
233  timer.tic();
234  SMOOTH(NBT)
235  {
237  model, data, qs[_smooth], qdots[_smooth], qddots[_smooth], contact_models_6D6D,
238  contact_datas_6D6D);
240  model, data, contact_models_6D6D, contact_datas_6D6D);
241  }
242  std::cout << "contact dynamics derivatives 6D,6D = \t\t";
243  timer.toc(std::cout, NBT);
244 
245  timer.tic();
246  SMOOTH(NBT)
247  {
248  constraint_dynamics_derivatives_code_gen.evalFunction(
249  qs[_smooth], qdots[_smooth], qddots[_smooth]);
250  }
251  std::cout << "contact dynamics derivatives 6D,6D code gen = \t\t";
252  timer.toc(std::cout, NBT);
253 
254  return 0;
255 }
pinocchio::WORLD
@ WORLD
Definition: multibody/fwd.hpp:48
PinocchioTicToc::toc
double toc()
Definition: timer.hpp:88
pinocchio::CodeGenBase::initLib
void initLib()
Definition: code-generator-base.hpp:78
pinocchio::CodeGenABA::evalFunction
void evalFunction(const Eigen::MatrixBase< ConfigVectorType > &q, const Eigen::MatrixBase< TangentVector1 > &v, const Eigen::MatrixBase< TangentVector2 > &tau)
Definition: code-generator-algo.hpp:198
Eigen
pinocchio::CodeGenMinv
Definition: code-generator-algo.hpp:358
pinocchio::DataTpl
Definition: context/generic.hpp:25
cppadcg.hpp
compute-all-terms.hpp
pinocchio::computeConstraintDynamicsDerivatives
void computeConstraintDynamicsDerivatives(const ModelTpl< Scalar, Options, JointCollectionTpl > &model, DataTpl< Scalar, Options, JointCollectionTpl > &data, const std::vector< RigidConstraintModelTpl< Scalar, Options >, ConstraintModelAllocator > &contact_models, std::vector< RigidConstraintDataTpl< Scalar, Options >, ConstraintDataAllocator > &contact_data, const ProximalSettingsTpl< Scalar > &settings, const Eigen::MatrixBase< MatrixType1 > &ddq_partial_dq, const Eigen::MatrixBase< MatrixType2 > &ddq_partial_dv, const Eigen::MatrixBase< MatrixType3 > &ddq_partial_dtau, const Eigen::MatrixBase< MatrixType4 > &lambda_partial_dq, const Eigen::MatrixBase< MatrixType5 > &lambda_partial_dv, const Eigen::MatrixBase< MatrixType6 > &lambda_partial_dtau)
aligned-vector.hpp
pinocchio::CodeGenRNEADerivatives::evalFunction
void evalFunction(const Eigen::MatrixBase< ConfigVectorType > &q, const Eigen::MatrixBase< TangentVector1 > &v, const Eigen::MatrixBase< TangentVector2 > &a)
Definition: code-generator-algo.hpp:527
pinocchio::CodeGenRNEA::evalFunction
void evalFunction(const Eigen::MatrixBase< ConfigVectorType > &q, const Eigen::MatrixBase< TangentVector1 > &v, const Eigen::MatrixBase< TangentVector2 > &a)
Definition: code-generator-algo.hpp:79
inverse-kinematics.i
int i
Definition: inverse-kinematics.py:20
code-generator-algo.hpp
kinematics.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::python::context::JointModelFreeFlyer
JointModelFreeFlyerTpl< Scalar > JointModelFreeFlyer
Definition: bindings/python/context/generic.hpp:124
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::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...
main
int main(int argc, const char **argv)
Definition: timings-cg.cpp:30
constrained-dynamics-derivatives.hpp
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
pinocchio::CONTACT_6D
@ CONTACT_6D
Point contact model.
Definition: algorithm/contact-info.hpp:22
rnea.hpp
timer.hpp
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.
pinocchio::CodeGenMinv::evalFunction
void evalFunction(const Eigen::MatrixBase< ConfigVectorType > &q)
Definition: code-generator-algo.hpp:414
aba.hpp
anymal-simulation.model
model
Definition: anymal-simulation.py:12
center-of-mass.hpp
SMOOTH
#define SMOOTH(s)
Definition: timer.hpp:38
joint-configuration.hpp
pinocchio::CodeGenBase::loadLib
void loadLib(const bool generate_if_not_exist=true, const std::string &gcc_path="/usr/bin/gcc", const std::string &compile_options="-Ofast")
Definition: code-generator-base.hpp:123
pinocchio::RigidConstraintModelTpl
Definition: algorithm/constraints/fwd.hpp:14
pinocchio::urdf::buildModel
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...
filename
filename
pinocchio::CodeGenABADerivatives
Definition: code-generator-algo.hpp:570
urdf.hpp
pinocchio::RigidConstraintDataTpl
Definition: algorithm/constraints/fwd.hpp:16
pinocchio::initConstraintDynamics
void initConstraintDynamics(const ModelTpl< Scalar, Options, JointCollectionTpl > &model, DataTpl< Scalar, Options, JointCollectionTpl > &data, const std::vector< RigidConstraintModelTpl< Scalar, Options >, Allocator > &contact_models)
Init the forward dynamics data according to the contact information contained in contact_models.
pinocchio::CodeGenABA
Definition: code-generator-algo.hpp:142
pinocchio::CodeGenABADerivatives::evalFunction
void evalFunction(const Eigen::MatrixBase< ConfigVectorType > &q, const Eigen::MatrixBase< TangentVector1 > &v, const Eigen::MatrixBase< TangentVector2 > &tau)
Definition: code-generator-algo.hpp:646
pinocchio::CodeGenCRBA
Definition: code-generator-algo.hpp:262
PINOCCHIO_STD_VECTOR_WITH_EIGEN_ALLOCATOR
#define PINOCCHIO_STD_VECTOR_WITH_EIGEN_ALLOCATOR(T)
Definition: container/aligned-vector.hpp:13
pinocchio::CodeGenABA::evalJacobian
void evalJacobian(const Eigen::MatrixBase< ConfigVectorType > &q, const Eigen::MatrixBase< TangentVector1 > &v, const Eigen::MatrixBase< TangentVector2 > &tau)
Definition: code-generator-algo.hpp:218
PinocchioTicToc::US
@ US
Definition: timer.hpp:53
cholesky.hpp
pinocchio::container::aligned_vector
std::vector< T, Eigen::aligned_allocator< T > > aligned_vector
Definition: container/aligned-vector.hpp:21
pinocchio::CodeGenRNEA::evalJacobian
void evalJacobian(const Eigen::MatrixBase< ConfigVectorType > &q, const Eigen::MatrixBase< TangentVector1 > &v, const Eigen::MatrixBase< TangentVector2 > &a)
Definition: code-generator-algo.hpp:99
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...
contact-info.hpp
pinocchio::CodeGenCRBA::evalFunction
void evalFunction(const Eigen::MatrixBase< ConfigVectorType > &q)
Definition: code-generator-algo.hpp:319
sample-models.hpp
pinocchio::CodeGenConstraintDynamicsDerivatives::evalFunction
void evalFunction(const Eigen::MatrixBase< ConfigVectorType > &q, const Eigen::MatrixBase< TangentVector1 > &v, const Eigen::MatrixBase< TangentVector2 > &tau)
Definition: code-generator-algo.hpp:820
jacobian.hpp
pinocchio::ModelTpl
Definition: context/generic.hpp:20
constrained-dynamics.hpp
crba.hpp
pinocchio::CodeGenRNEADerivatives
Definition: code-generator-algo.hpp:451
PinocchioTicToc
Definition: timer.hpp:47
meshcat-viewer.qs
qs
Definition: meshcat-viewer.py:127
pinocchio::constraintDynamics
const DataTpl< Scalar, Options, JointCollectionTpl >::TangentVectorType & constraintDynamics(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 std::vector< RigidConstraintModelTpl< Scalar, Options >, ConstraintModelAllocator > &contact_models, std::vector< RigidConstraintDataTpl< Scalar, Options >, ConstraintDataAllocator > &contact_datas, ProximalSettingsTpl< Scalar > &settings)
Computes the forward dynamics with contact constraints according to a given list of Contact informati...
pinocchio::CodeGenRNEA
Definition: code-generator-algo.hpp:22
pinocchio
Main pinocchio namespace.
Definition: timings.cpp:27
pinocchio::CodeGenConstraintDynamicsDerivatives
Definition: code-generator-algo.hpp:689
PINOCCHIO_MODEL_DIR
#define PINOCCHIO_MODEL_DIR
Definition: build-reduced-model.cpp:11
PinocchioTicToc::tic
void tic()
Definition: timer.hpp:82


pinocchio
Author(s):
autogenerated on Sat Jun 1 2024 02:40:38