timings-impulse-dynamics-derivatives.cpp
Go to the documentation of this file.
1 //
2 // Copyright (c) 2020-2025 LAAS-CNRS, INRIA
3 //
4 
5 #include "model-fixture.hpp"
6 
13 
14 #include <benchmark/benchmark.h>
15 
16 #include <iostream>
17 
19 {
20  void SetUp(benchmark::State & st)
21  {
23 
24  const std::string RF = "RLEG_LINK6";
25  const auto RF_id = model.frames[model.getFrameId(RF)].parentJoint;
26  const std::string LF = "LLEG_LINK6";
27  const auto LF_id = model.frames[model.getFrameId(LF)].parentJoint;
28 
29  ci_RF_6D = std::make_unique<pinocchio::RigidConstraintModel>(
31  ci_LF_6D = std::make_unique<pinocchio::RigidConstraintModel>(
33 
35 
36  contact_models_6D.clear();
37  contact_models_6D.push_back(*ci_RF_6D);
38 
39  contact_data_6D.clear();
40  contact_data_6D.push_back(pinocchio::RigidConstraintData(*ci_RF_6D));
41 
43 
44  contact_models_6D6D.clear();
45  contact_models_6D6D.push_back(*ci_RF_6D);
46  contact_models_6D6D.push_back(*ci_LF_6D);
47 
48  contact_data_6D6D.clear();
49  contact_data_6D6D.push_back(pinocchio::RigidConstraintData(*ci_RF_6D));
50  contact_data_6D6D.push_back(pinocchio::RigidConstraintData(*ci_LF_6D));
51 
53 
54  r_coeff = (Eigen::ArrayXd::Random(1)[0] + 1.) / 2.;
55 
57  prox_settings.mu = 1e8;
58  }
59 
60  void TearDown(benchmark::State & st)
61  {
63  }
64 
65  std::unique_ptr<pinocchio::RigidConstraintModel> ci_RF_6D;
66  std::unique_ptr<pinocchio::RigidConstraintModel> ci_LF_6D;
67 
74 
78 
79  double r_coeff;
80 
82 };
83 
84 static void CustomArguments(benchmark::internal::Benchmark * b)
85 {
86  b->MinWarmUpTime(3.);
87 }
88 
89 // IMPULSE_DYNAMICS_DERIVATIVES_EMPTY
90 
92  const pinocchio::Model & model,
96  double r_coeff,
98 {
101 }
102 BENCHMARK_DEFINE_F(ContactFixture, IMPULSE_DYNAMICS_DERIVATIVES_EMPTY)(benchmark::State & st)
103 {
104  pinocchio::initConstraintDynamics(model, data, contact_models_empty);
106  model, data, q, v, contact_models_empty, contact_data_empty, r_coeff, prox_settings);
107  for (auto _ : st)
108  {
110  model, data, contact_models_empty, contact_data_empty, r_coeff, prox_settings);
111  }
112 }
113 BENCHMARK_REGISTER_F(ContactFixture, IMPULSE_DYNAMICS_DERIVATIVES_EMPTY)->Apply(CustomArguments);
114 
115 // IMPULSE_DYNAMICS_DERIVATIVES_6D
116 
117 BENCHMARK_DEFINE_F(ContactFixture, IMPULSE_DYNAMICS_DERIVATIVES_6D)(benchmark::State & st)
118 {
119  pinocchio::initConstraintDynamics(model, data, contact_models_6D);
121  model, data, q, v, contact_models_6D, contact_data_6D, r_coeff, prox_settings);
122  for (auto _ : st)
123  {
125  model, data, contact_models_6D, contact_data_6D, r_coeff, prox_settings);
126  }
127 }
128 BENCHMARK_REGISTER_F(ContactFixture, IMPULSE_DYNAMICS_DERIVATIVES_6D)->Apply(CustomArguments);
129 
130 // IMPULSE_DYNAMICS_DERIVATIVES_6D6D
131 
132 BENCHMARK_DEFINE_F(ContactFixture, IMPULSE_DYNAMICS_DERIVATIVES_6D6D)(benchmark::State & st)
133 {
134  pinocchio::initConstraintDynamics(model, data, contact_models_6D6D);
136  model, data, q, v, contact_models_6D6D, contact_data_6D6D, r_coeff, prox_settings);
137  for (auto _ : st)
138  {
140  model, data, contact_models_6D6D, contact_data_6D6D, r_coeff, prox_settings);
141  }
142 }
143 BENCHMARK_REGISTER_F(ContactFixture, IMPULSE_DYNAMICS_DERIVATIVES_6D6D)->Apply(CustomArguments);
144 
BENCHMARK_REGISTER_F
BENCHMARK_REGISTER_F(ContactFixture, IMPULSE_DYNAMICS_DERIVATIVES_EMPTY) -> Apply(CustomArguments)
BENCHMARK_DEFINE_F
BENCHMARK_DEFINE_F(ContactFixture, IMPULSE_DYNAMICS_DERIVATIVES_EMPTY)(benchmark
Definition: timings-impulse-dynamics-derivatives.cpp:102
pinocchio::ModelTpl::frames
FrameVector frames
Vector of operational frames registered on the model.
Definition: multibody/model.hpp:193
pinocchio::DataTpl
Definition: context/generic.hpp:25
PINOCCHIO_DONT_INLINE
#define PINOCCHIO_DONT_INLINE
Function attribute to forbid inlining. This is a compiler hint that can be not respected.
Definition: include/pinocchio/macros.hpp:53
pinocchio::ProximalSettingsTpl::mu
Scalar mu
Regularization parameter of the proximal algorithm.
Definition: algorithm/proximal.hpp:95
ModelFixture::model
pinocchio::Model model
Definition: model-fixture.hpp:79
ModelFixture::TearDown
void TearDown(benchmark::State &)
Definition: model-fixture.hpp:51
ModelFixture
Definition: model-fixture.hpp:37
ContactFixture::contact_chol_6D
pinocchio::ContactCholeskyDecomposition contact_chol_6D
Definition: timings-constrained-dynamics-derivatives.cpp:73
contact-cholesky.contact_data
list contact_data
Definition: contact-cholesky.py:33
setup.data
data
Definition: cmake/cython/setup.in.py:48
ContactFixture::TearDown
void TearDown(benchmark::State &st)
Definition: timings-impulse-dynamics-derivatives.cpp:60
impulse-dynamics-derivatives.hpp
pinocchio::CONTACT_6D
@ CONTACT_6D
Point contact model.
Definition: algorithm/contact-info.hpp:22
bindings_dynamics.r_coeff
float r_coeff
Definition: bindings_dynamics.py:10
b
Vec3f b
ModelFixture::SetUp
void SetUp(benchmark::State &)
Definition: model-fixture.hpp:39
anymal-simulation.model
model
Definition: anymal-simulation.py:8
joint-configuration.hpp
pinocchio::ProximalSettingsTpl
Structure containing all the settings parameters for the proximal algorithms.
Definition: algorithm/fwd.hpp:13
ContactFixture::contact_chol_empty
pinocchio::ContactCholeskyDecomposition contact_chol_empty
Definition: timings-constrained-dynamics-derivatives.cpp:72
pinocchio::RigidConstraintModelTpl
Definition: algorithm/constraints/fwd.hpp:14
ContactFixture::ci_RF_6D
std::unique_ptr< pinocchio::RigidConstraintModel > ci_RF_6D
Definition: timings-constrained-dynamics-derivatives.cpp:62
PINOCCHIO_BENCHMARK_MAIN
PINOCCHIO_BENCHMARK_MAIN()
model-fixture.hpp
pinocchio::ModelTpl::getFrameId
FrameIndex getFrameId(const std::string &name, const FrameType &type=(FrameType)(JOINT|FIXED_JOINT|BODY|OP_FRAME|SENSOR)) const
Returns the index of a frame given by its name.
urdf.hpp
pinocchio::RigidConstraintDataTpl
Definition: algorithm/constraints/fwd.hpp:16
cartpole.v
v
Definition: cartpole.py:153
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::computeImpulseDynamicsDerivatives
void computeImpulseDynamicsDerivatives(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 Scalar r_coeff, const ProximalSettingsTpl< Scalar > &settings, const Eigen::MatrixBase< MatrixType1 > &dvimpulse_partial_dq, const Eigen::MatrixBase< MatrixType2 > &dvimpulse_partial_dv, const Eigen::MatrixBase< MatrixType3 > &impulse_partial_dq, const Eigen::MatrixBase< MatrixType4 > &impulse_partial_dv)
ContactFixture::r_coeff
double r_coeff
Definition: timings-impulse-dynamics-derivatives.cpp:79
inverse-dynamics._
_
Definition: inverse-dynamics.py:22
ContactFixture
Definition: timings-constrained-dynamics-derivatives.cpp:20
q
q
PINOCCHIO_STD_VECTOR_WITH_EIGEN_ALLOCATOR
#define PINOCCHIO_STD_VECTOR_WITH_EIGEN_ALLOCATOR(T)
Definition: container/aligned-vector.hpp:13
cholesky.hpp
ContactFixture::prox_settings
pinocchio::ProximalSettings prox_settings
Definition: timings-contact-dynamics.cpp:90
impulse-dynamics.hpp
pinocchio::ContactCholeskyDecomposition
ContactCholeskyDecompositionTpl< context::Scalar, context::Options > ContactCholeskyDecomposition
Definition: algorithm/fwd.hpp:17
pinocchio::ProximalSettingsTpl::max_iter
int max_iter
Maximal number of iterations.
Definition: algorithm/proximal.hpp:98
ContactFixture::contact_chol_6D6D
pinocchio::ContactCholeskyDecomposition contact_chol_6D6D
Definition: timings-constrained-dynamics-derivatives.cpp:74
pinocchio::impulseDynamics
const PINOCCHIO_DEPRECATED DataTpl< Scalar, Options, JointCollectionTpl >::TangentVectorType & impulseDynamics(const ModelTpl< Scalar, Options, JointCollectionTpl > &model, DataTpl< Scalar, Options, JointCollectionTpl > &data, const Eigen::MatrixBase< ConfigVectorType > &q, const Eigen::MatrixBase< TangentVectorType > &v_before, const Eigen::MatrixBase< ConstraintMatrixType > &J, const Scalar r_coeff=0., const Scalar inv_damping=0.)
Compute the impulse dynamics with contact constraints. Internally, pinocchio::crba is called.
CustomArguments
static void CustomArguments(benchmark::internal::Benchmark *b)
Definition: timings-impulse-dynamics-derivatives.cpp:84
contact-cholesky.contact_models
list contact_models
Definition: contact-cholesky.py:22
pinocchio::ContactCholeskyDecompositionTpl< context::Scalar, context::Options >
sample-models.hpp
pinocchio::ModelTpl< context::Scalar, context::Options >
ContactFixture::PINOCCHIO_STD_VECTOR_WITH_EIGEN_ALLOCATOR
PINOCCHIO_STD_VECTOR_WITH_EIGEN_ALLOCATOR(pinocchio::RigidConstraintModel) contact_models_empty
simulation-closed-kinematic-chains.prox_settings
prox_settings
Definition: simulation-closed-kinematic-chains.py:158
ContactFixture::SetUp
void SetUp(benchmark::State &st)
Definition: timings-impulse-dynamics-derivatives.cpp:20
ContactFixture::ci_LF_6D
std::unique_ptr< pinocchio::RigidConstraintModel > ci_LF_6D
Definition: timings-constrained-dynamics-derivatives.cpp:63
impulseDynamicsDerivativesCall
static PINOCCHIO_DONT_INLINE void impulseDynamicsDerivativesCall(const pinocchio::Model &model, pinocchio::Data &data, const PINOCCHIO_STD_VECTOR_WITH_EIGEN_ALLOCATOR(pinocchio::RigidConstraintModel) &contact_models, PINOCCHIO_STD_VECTOR_WITH_EIGEN_ALLOCATOR(pinocchio::RigidConstraintData) &contact_data, double r_coeff, const pinocchio::ProximalSettings &prox_settings)
Definition: timings-impulse-dynamics-derivatives.cpp:91
pinocchio::LOCAL
@ LOCAL
Definition: multibody/fwd.hpp:50


pinocchio
Author(s):
autogenerated on Wed Apr 16 2025 02:41:51