cppad/algorithms.cpp
Go to the documentation of this file.
1 //
2 // Copyright (c) 2018-2022 CNRS INRIA
3 //
4 
6 
9 
16 
18 
19 #include <iostream>
20 
21 #include <boost/test/unit_test.hpp>
22 #include <boost/utility/binary.hpp>
23 
24 #ifdef _WIN32
25  #define DLL_EXT ".dll"
26 #else
27  #define DLL_EXT ".so"
28 #endif
29 
30 BOOST_AUTO_TEST_SUITE(BOOST_TEST_MODULE)
31 
32 BOOST_AUTO_TEST_CASE(test_mass_matrix)
33 {
34  using CppAD::AD;
35  using CppAD::NearEqual;
36 
37  typedef double Scalar;
38  typedef AD<Scalar> ADScalar;
39 
41  typedef Model::Data Data;
42 
43  typedef pinocchio::ModelTpl<ADScalar> ADModel;
44  typedef ADModel::Data ADData;
45 
46  Model model;
48  model.lowerPositionLimit.head<3>().fill(-1.);
49  model.upperPositionLimit.head<3>().fill(1.);
50  Data data(model);
51 
52  ADModel ad_model = model.cast<ADScalar>();
53  ADData ad_data(ad_model);
54 
55  // Sample random configuration
56  typedef Model::ConfigVectorType ConfigVectorType;
57  typedef Model::TangentVectorType TangentVectorType;
58  ConfigVectorType q(model.nq);
60 
61  TangentVectorType v(TangentVectorType::Random(model.nv));
62  TangentVectorType a(TangentVectorType::Random(model.nv));
63 
64  typedef ADModel::ConfigVectorType ADConfigVectorType;
65  typedef ADModel::TangentVectorType ADTangentVectorType;
66 
67  ADConfigVectorType ad_q = q.cast<ADScalar>();
68  ADTangentVectorType ad_v = v.cast<ADScalar>();
69  ADTangentVectorType ad_a = a.cast<ADScalar>();
70 
71  typedef Eigen::Matrix<ADScalar, Eigen::Dynamic, 1> VectorXAD;
73  data.M.triangularView<Eigen::StrictlyLower>() =
74  data.M.transpose().triangularView<Eigen::StrictlyLower>();
75 
76  Data::TangentVectorType tau = pinocchio::rnea(model, data, q, v, a);
77 
78  {
79  CppAD::Independent(ad_a);
80  pinocchio::rnea(ad_model, ad_data, ad_q, ad_v, ad_a);
81 
82  VectorXAD Y(model.nv);
83  Eigen::Map<ADData::TangentVectorType>(Y.data(), model.nv, 1) = ad_data.tau;
84 
85  CppAD::ADFun<Scalar> ad_fun(ad_a, Y);
86 
87  CPPAD_TESTVECTOR(Scalar) x((size_t)model.nv);
88  Eigen::Map<Data::TangentVectorType>(x.data(), model.nv, 1) = a;
89 
90  CPPAD_TESTVECTOR(Scalar) tau = ad_fun.Forward(0, x);
91  BOOST_CHECK(Eigen::Map<Data::TangentVectorType>(tau.data(), model.nv, 1).isApprox(data.tau));
92 
93  CPPAD_TESTVECTOR(Scalar) dtau_da = ad_fun.Jacobian(x);
94  Data::MatrixXs M = Eigen::Map<PINOCCHIO_EIGEN_PLAIN_ROW_MAJOR_TYPE(Data::MatrixXs)>(
95  dtau_da.data(), model.nv, model.nv);
96  BOOST_CHECK(M.isApprox(data.M));
97  }
98 
99  ADTangentVectorType ad_tau = tau.cast<ADScalar>();
100 
102  data.Minv.triangularView<Eigen::StrictlyLower>() =
103  data.Minv.transpose().triangularView<Eigen::StrictlyLower>();
104 
106  {
107  CppAD::Independent(ad_tau);
108  pinocchio::aba(ad_model, ad_data, ad_q, ad_v, ad_tau, pinocchio::Convention::WORLD);
109 
110  VectorXAD Y(model.nv);
111  Eigen::Map<ADData::TangentVectorType>(Y.data(), model.nv, 1) = ad_data.ddq;
112 
113  CppAD::ADFun<Scalar> ad_fun(ad_tau, Y);
114 
115  CPPAD_TESTVECTOR(Scalar) x((size_t)model.nv);
116  Eigen::Map<Data::TangentVectorType>(x.data(), model.nv, 1) = tau;
117 
118  CPPAD_TESTVECTOR(Scalar) ddq = ad_fun.Forward(0, x);
119  BOOST_CHECK(Eigen::Map<Data::TangentVectorType>(ddq.data(), model.nv, 1).isApprox(a));
120 
121  CPPAD_TESTVECTOR(Scalar) dddq_da = ad_fun.Jacobian(x);
122  Data::MatrixXs Minv = Eigen::Map<PINOCCHIO_EIGEN_PLAIN_ROW_MAJOR_TYPE(Data::MatrixXs)>(
123  dddq_da.data(), model.nv, model.nv);
124  BOOST_CHECK(Minv.isApprox(data.Minv));
125  }
126 }
127 
128 BOOST_AUTO_TEST_CASE(test_kinematics_jacobian)
129 {
130  using CppAD::AD;
131  using CppAD::NearEqual;
132 
133  typedef double Scalar;
134  typedef AD<Scalar> ADScalar;
135 
137  typedef Model::Data Data;
138  typedef Model::Motion Motion;
139 
140  typedef pinocchio::ModelTpl<ADScalar> ADModel;
141  typedef ADModel::Data ADData;
142 
143  Model model;
145  model.lowerPositionLimit.head<3>().fill(-1.);
146  model.upperPositionLimit.head<3>().fill(1.);
147  Data data(model);
148 
149  ADModel ad_model = model.cast<ADScalar>();
150  ADData ad_data(ad_model);
151 
152  // Sample random configuration
153  typedef Model::ConfigVectorType ConfigVectorType;
154  typedef Model::TangentVectorType TangentVectorType;
155  ConfigVectorType q(model.nq);
157 
158  TangentVectorType v(TangentVectorType::Random(model.nv));
159  TangentVectorType a(TangentVectorType::Random(model.nv));
160 
161  typedef ADModel::ConfigVectorType ADConfigVectorType;
162  typedef ADModel::TangentVectorType ADTangentVectorType;
163 
164  ADConfigVectorType ad_q = q.cast<ADScalar>();
165  ADTangentVectorType ad_v = v.cast<ADScalar>();
166  ADTangentVectorType ad_a = a.cast<ADScalar>();
167 
168  // Test if the jacobian of a precise link is given by dv_link/dv
169  const std::string joint_name = "rarm5_joint";
173 
174  Data::Matrix6x J_local(6, model.nv), J_global(6, model.nv);
175  J_local.setZero();
176  J_global.setZero();
177  Data::Matrix6x dJ_local(6, model.nv), dJ_global(6, model.nv);
178  dJ_local.setZero();
179  dJ_global.setZero();
182 
185 
186  const ADData::Motion & v_local = ad_data.v[joint_id];
187  const ADData::Motion & a_local = ad_data.a[joint_id];
188 
189  typedef Eigen::Matrix<ADScalar, Eigen::Dynamic, 1> VectorXAD;
190 
191  {
192  CppAD::Independent(ad_v);
193  pinocchio::forwardKinematics(ad_model, ad_data, ad_q, ad_v, ad_a);
194 
195  const ADData::Motion v_global = ad_data.oMi[joint_id].act(v_local);
196 
197  VectorXAD Y(6 * 3);
198  Eigen::DenseIndex current_id = 0;
199  for (Eigen::DenseIndex k = 0; k < 3; ++k)
200  {
201  Y[current_id + k + Motion::LINEAR] = v_local.linear()[k];
202  Y[current_id + k + Motion::ANGULAR] = v_local.angular()[k];
203  }
204  current_id += 6;
205 
206  for (Eigen::DenseIndex k = 0; k < 3; ++k)
207  {
208  Y[current_id + k + Motion::LINEAR] = v_global.linear()[k];
209  Y[current_id + k + Motion::ANGULAR] = v_global.angular()[k];
210  }
211  current_id += 6;
212 
213  for (Eigen::DenseIndex k = 0; k < 3; ++k)
214  {
215  Y[current_id + k + Motion::LINEAR] = a_local.linear()[k];
216  Y[current_id + k + Motion::ANGULAR] = a_local.angular()[k];
217  }
218  current_id += 6;
219 
220  CppAD::ADFun<Scalar> vjoint(ad_v, Y);
221 
222  CPPAD_TESTVECTOR(Scalar) x((size_t)model.nv);
223  for (Eigen::DenseIndex k = 0; k < model.nv; ++k)
224  {
225  x[(size_t)k] = v[k];
226  }
227 
228  CPPAD_TESTVECTOR(Scalar) y = vjoint.Forward(0, x);
229  Scalar * y_ptr = y.data();
230  BOOST_CHECK(data.v[joint_id].isApprox(Motion(Eigen::Map<Motion::Vector6>(y_ptr))));
231  y_ptr += 6;
233  .act(data.v[joint_id])
234  .isApprox(Motion(Eigen::Map<Motion::Vector6>(y_ptr))));
235  y_ptr += 6;
236  BOOST_CHECK(data.a[joint_id].isApprox(Motion(Eigen::Map<Motion::Vector6>(y_ptr))));
237  y_ptr += 6;
238 
239  CPPAD_TESTVECTOR(Scalar) dY_dv = vjoint.Jacobian(x);
240 
241  Scalar * dY_dv_ptr = dY_dv.data();
242  Data::Matrix6x ad_J_local =
243  Eigen::Map<PINOCCHIO_EIGEN_PLAIN_ROW_MAJOR_TYPE(Data::Matrix6x)>(dY_dv_ptr, 6, model.nv);
244  dY_dv_ptr += ad_J_local.size();
245  Data::Matrix6x ad_J_global =
246  Eigen::Map<PINOCCHIO_EIGEN_PLAIN_ROW_MAJOR_TYPE(Data::Matrix6x)>(dY_dv_ptr, 6, model.nv);
247  dY_dv_ptr += ad_J_global.size();
248 
249  BOOST_CHECK(ad_J_local.isApprox(J_local));
250  BOOST_CHECK(ad_J_global.isApprox(J_global));
251  }
252 
253  {
254  CppAD::Independent(ad_a);
255  pinocchio::forwardKinematics(ad_model, ad_data, ad_q, ad_v, ad_a);
256 
257  VectorXAD Y(6 * 2);
258  Eigen::DenseIndex current_id = 0;
259  for (Eigen::DenseIndex k = 0; k < 3; ++k)
260  {
261  Y[current_id + k + Motion::LINEAR] = v_local.linear()[k];
262  Y[current_id + k + Motion::ANGULAR] = v_local.angular()[k];
263  }
264  current_id += 6;
265 
266  for (Eigen::DenseIndex k = 0; k < 3; ++k)
267  {
268  Y[current_id + k + Motion::LINEAR] = a_local.linear()[k];
269  Y[current_id + k + Motion::ANGULAR] = a_local.angular()[k];
270  }
271  current_id += 6;
272 
273  CppAD::ADFun<Scalar> ajoint(ad_a, Y);
274 
275  CPPAD_TESTVECTOR(Scalar) x((size_t)model.nv);
276  for (Eigen::DenseIndex k = 0; k < model.nv; ++k)
277  {
278  x[(size_t)k] = a[k];
279  }
280 
281  CPPAD_TESTVECTOR(Scalar) y = ajoint.Forward(0, x);
282  Scalar * y_ptr = y.data() + 6;
283  BOOST_CHECK(data.a[joint_id].isApprox(Motion(Eigen::Map<Motion::Vector6>(y_ptr))));
284  y_ptr += 6;
285 
286  CPPAD_TESTVECTOR(Scalar) dY_da = ajoint.Jacobian(x);
287 
288  Scalar * dY_da_ptr = dY_da.data();
289  Data::Matrix6x ad_dv_da =
290  Eigen::Map<PINOCCHIO_EIGEN_PLAIN_ROW_MAJOR_TYPE(Data::Matrix6x)>(dY_da_ptr, 6, model.nv);
291  dY_da_ptr += ad_dv_da.size();
292  Data::Matrix6x ad_J_local =
293  Eigen::Map<PINOCCHIO_EIGEN_PLAIN_ROW_MAJOR_TYPE(Data::Matrix6x)>(dY_da_ptr, 6, model.nv);
294  dY_da_ptr += ad_J_local.size();
295 
296  BOOST_CHECK(ad_dv_da.isZero());
297  BOOST_CHECK(ad_J_local.isApprox(J_local));
298  }
299 }
300 
301 BOOST_AUTO_TEST_CASE(test_JSIM_jit)
302 {
303  using CppAD::AD;
304  using CppAD::NearEqual;
305 
306  typedef double Scalar;
307  typedef AD<Scalar> ADScalar;
308 
310  typedef Model::Data Data;
311 
312  typedef pinocchio::ModelTpl<ADScalar> ADModel;
313  typedef ADModel::Data ADData;
314 
315  Model model;
317  model.lowerPositionLimit.head<3>().fill(-1.);
318  model.upperPositionLimit.head<3>().fill(1.);
319  Data data(model);
320 
321  ADModel ad_model = model.cast<ADScalar>();
322  ADData ad_data(ad_model);
323 
324  // Sample random configuration
325  typedef Model::ConfigVectorType ConfigVectorType;
326  typedef Model::TangentVectorType TangentVectorType;
327  ConfigVectorType q(model.nq);
329 
330  TangentVectorType v(TangentVectorType::Random(model.nv));
331  TangentVectorType a(TangentVectorType::Random(model.nv));
332 
333  typedef ADModel::ConfigVectorType ADConfigVectorType;
334  typedef ADModel::TangentVectorType ADTangentVectorType;
335 
336  ADConfigVectorType ad_q = q.cast<ADScalar>();
337  ADTangentVectorType ad_v = v.cast<ADScalar>();
338  ADTangentVectorType ad_a = a.cast<ADScalar>();
339 
340  typedef Eigen::Matrix<ADScalar, Eigen::Dynamic, 1> VectorXAD;
341  typedef Eigen::Matrix<ADScalar, Eigen::Dynamic, Eigen::Dynamic> MatrixXAD;
343  data.M.triangularView<Eigen::StrictlyLower>() =
344  data.M.transpose().triangularView<Eigen::StrictlyLower>();
345 
346  pinocchio::rnea(model, data, q, v, a);
347  {
348  CppAD::Independent(ad_a);
349  pinocchio::rnea(ad_model, ad_data, ad_q, ad_v, ad_a);
350 
351  VectorXAD Y(model.nv);
352  Eigen::Map<ADData::TangentVectorType>(Y.data(), model.nv, 1) = ad_data.tau;
353 
354  CppAD::ADFun<Scalar> f(ad_a, Y);
355  CppAD::ADFun<ADScalar, Scalar> af = f.base2ad();
356 
357  CppAD::Independent(ad_a);
358  MatrixXAD dtau_da = af.Jacobian(ad_a);
359  VectorXAD dtau_da_vector(model.nv * model.nv);
360  dtau_da_vector = Eigen::Map<VectorXAD>(dtau_da.data(), dtau_da.cols() * dtau_da.rows());
361  CppAD::ADFun<double> ad_fun(ad_a, dtau_da_vector);
362 
363  ad_fun.function_name_set("ad_fun");
364 
365  // create csrc_file
366  std::string c_type = "double";
367  std::string csrc_file = "jit_JSIM.c";
368  std::ofstream ofs;
369  ofs.open(csrc_file, std::ofstream::out);
370  ad_fun.to_csrc(ofs, c_type);
371  ofs.close();
372 
373  // create dll_file
374  std::string dll_file = "./jit_JSIM" DLL_EXT;
375  CPPAD_TESTVECTOR(std::string) csrc_files(1);
376  csrc_files[0] = csrc_file;
377  std::map<std::string, std::string> options;
378  std::string err_msg = CppAD::create_dll_lib(dll_file, csrc_files, options);
379  if (err_msg != "")
380  {
381  std::cerr << "jit_JSIM: err_msg = " << err_msg << "\n";
382  }
383 
384  // dll_linker
385  CppAD::link_dll_lib dll_linker(dll_file, err_msg);
386  if (err_msg != "")
387  {
388  std::cerr << "jit_JSIM: err_msg = " << err_msg << "\n";
389  }
390 
391  std::string function_name = "cppad_jit_ad_fun";
392  void * void_ptr = dll_linker(function_name, err_msg);
393  if (err_msg != "")
394  {
395  std::cerr << "jit_JSIM: err_msg = " << err_msg << "\n";
396  }
397 
398  using CppAD::jit_double;
399  jit_double ad_fun_ptr = reinterpret_cast<jit_double>(void_ptr);
400 
401  CPPAD_TESTVECTOR(Scalar) x((size_t)model.nv);
402  Eigen::Map<Data::TangentVectorType>(x.data(), model.nv, 1) = a;
403 
404  size_t compare_change = 0, nx = (size_t)model.nv,
405  ndtau_da_ = (size_t)model.nv * (size_t)model.nv;
406  std::vector<double> dtau_da_jit(ndtau_da_);
407  ad_fun_ptr(nx, x.data(), ndtau_da_, dtau_da_jit.data(), &compare_change);
408 
409  Data::MatrixXs M = Eigen::Map<PINOCCHIO_EIGEN_PLAIN_ROW_MAJOR_TYPE(Data::MatrixXs)>(
410  dtau_da_jit.data(), model.nv, model.nv);
411  BOOST_CHECK(M.isApprox(data.M));
412  }
413 }
414 
415 BOOST_AUTO_TEST_SUITE_END()
pinocchio::WORLD
@ WORLD
Definition: multibody/fwd.hpp:48
pinocchio::getJointJacobianTimeVariation
void getJointJacobianTimeVariation(const ModelTpl< Scalar, Options, JointCollectionTpl > &model, const DataTpl< Scalar, Options, JointCollectionTpl > &data, const JointIndex joint_id, const ReferenceFrame reference_frame, const Eigen::MatrixBase< Matrix6Like > &dJ)
Computes the Jacobian time variation of a specific joint frame expressed either in the world frame (r...
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.
y
y
pinocchio::Convention::WORLD
@ WORLD
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::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::python::context::Motion
MotionTpl< Scalar, Options > Motion
Definition: bindings/python/context/generic.hpp:54
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
rnea.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.
aba.hpp
collision-with-point-clouds.nx
int nx
Definition: collision-with-point-clouds.py:38
anymal-simulation.model
model
Definition: anymal-simulation.py:12
forward-dynamics-derivatives.tau
tau
Definition: forward-dynamics-derivatives.py:23
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
pinocchio::context::MatrixXs
Eigen::Matrix< Scalar, Eigen::Dynamic, Eigen::Dynamic, Options > MatrixXs
Definition: context/generic.hpp:49
pinocchio::getJointJacobian
void getJointJacobian(const ModelTpl< Scalar, Options, JointCollectionTpl > &model, const DataTpl< Scalar, Options, JointCollectionTpl > &data, const JointIndex joint_id, const ReferenceFrame reference_frame, const Eigen::MatrixBase< Matrix6Like > &J)
Computes the Jacobian of a specific joint frame expressed in one of the pinocchio::ReferenceFrame opt...
data.hpp
x
x
M
M
q
q
cppad.hpp
BOOST_AUTO_TEST_CASE
BOOST_AUTO_TEST_CASE(test_mass_matrix)
Definition: cppad/algorithms.cpp:32
autodiff-rnea.dtau_da
dtau_da
Definition: autodiff-rnea.py:29
a
Vec3f a
Matrix6x
Eigen::Matrix< double, 6, Eigen::Dynamic > Matrix6x
Definition: joint-mimic.cpp:15
append-urdf-model-with-another-model.joint_name
string joint_name
Definition: append-urdf-model-with-another-model.py:33
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...
pinocchio::JointIndex
Index JointIndex
Definition: multibody/fwd.hpp:26
Y
Y
DLL_EXT
#define DLL_EXT
Definition: cppad/algorithms.cpp:27
sample-models.hpp
append-urdf-model-with-another-model.joint_id
joint_id
Definition: append-urdf-model-with-another-model.py:34
jacobian.hpp
pinocchio::ModelTpl
Definition: context/generic.hpp:20
crba.hpp
BOOST_CHECK
#define BOOST_CHECK(check)
Definition: overview-urdf.cpp:34
pinocchio::LOCAL
@ LOCAL
Definition: multibody/fwd.hpp:50


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