GCC Code Coverage Report


Directory: ./
File: include/pinocchio/autodiff/casadi.hpp
Date: 2025-02-12 21:03:38
Exec Total Coverage
Lines: 34 38 89.5%
Branches: 30 48 62.5%

Line Branch Exec Source
1 //
2 // Copyright (c) 2019-2024 INRIA CNRS
3 //
4
5 #ifndef __pinocchio_autodiff_casadi_hpp__
6 #define __pinocchio_autodiff_casadi_hpp__
7
8 #define PINOCCHIO_WITH_CASADI_SUPPORT
9
10 #include "pinocchio/math/fwd.hpp"
11
12 #include <casadi/casadi.hpp>
13 #include <Eigen/Core>
14 #include <Eigen/Sparse>
15
16 namespace boost
17 {
18 namespace math
19 {
20 namespace constants
21 {
22 namespace detail
23 {
24 template<>
25 struct constant_pi<::casadi::SX> : constant_pi<double>
26 {
27 };
28
29 template<typename Scalar>
30 struct constant_pi<::casadi::Matrix<Scalar>> : constant_pi<Scalar>
31 {
32 };
33 } // namespace detail
34 } // namespace constants
35 } // namespace math
36 } // namespace boost
37
38 // This is a workaround to make the code compiling with Eigen.
39 namespace casadi
40 {
41 inline bool operator||(const bool x, const ::casadi::Matrix<SXElem> & /*y*/)
42 {
43 return x;
44 }
45 } // namespace casadi
46
47 namespace pinocchio
48 {
49 template<typename Scalar>
50 struct TaylorSeriesExpansion<::casadi::Matrix<Scalar>> : TaylorSeriesExpansion<Scalar>
51 {
52 typedef TaylorSeriesExpansion<Scalar> Base;
53
54 template<int degree>
55 1044 static ::casadi::Matrix<Scalar> precision()
56 {
57
1/2
✓ Branch 2 taken 524 times.
✗ Branch 3 not taken.
1044 return ::casadi::Matrix<Scalar>(Base::template precision<degree>());
58 }
59 };
60
61 } // namespace pinocchio
62
63 namespace Eigen
64 {
65 namespace internal
66 {
67 // Specialization of Eigen::internal::cast_impl for Casadi input types
68 template<typename Scalar>
69 struct cast_impl<::casadi::Matrix<Scalar>, Scalar>
70 {
71 #if EIGEN_VERSION_AT_LEAST(3, 2, 90)
72 EIGEN_DEVICE_FUNC
73 #endif
74 static inline Scalar run(const ::casadi::Matrix<Scalar> & x)
75 {
76 return static_cast<Scalar>(x);
77 }
78 };
79
80 #if EIGEN_VERSION_AT_LEAST(3, 2, 90) && !EIGEN_VERSION_AT_LEAST(3, 2, 93)
81 template<typename Scalar, bool IsInteger>
82 struct significant_decimals_default_impl<::casadi::Matrix<Scalar>, IsInteger>
83 {
84 static inline int run()
85 {
86 return std::numeric_limits<Scalar>::digits10;
87 }
88 };
89 #endif
90 } // namespace internal
91 } // namespace Eigen
92
93 namespace Eigen
94 {
95 /// @brief Eigen::NumTraits<> specialization for casadi::SX
96 ///
97 template<typename Scalar>
98 struct NumTraits<::casadi::Matrix<Scalar>>
99 {
100 using Real = ::casadi::Matrix<Scalar>;
101 using NonInteger = ::casadi::Matrix<Scalar>;
102 using Literal = ::casadi::Matrix<Scalar>;
103 using Nested = ::casadi::Matrix<Scalar>;
104
105 enum
106 {
107 // does not support complex Base types
108 IsComplex = 0,
109 // does not support integer Base types
110 IsInteger = 0,
111 // only support signed Base types
112 IsSigned = 1,
113 // must initialize an AD<Base> object
114 RequireInitialization = 1,
115 // computational cost of the corresponding operations
116 ReadCost = 1,
117 AddCost = 2,
118 MulCost = 2
119 };
120
121 1189 static ::casadi::Matrix<Scalar> epsilon()
122 {
123 1189 return ::casadi::Matrix<Scalar>(std::numeric_limits<double>::epsilon());
124 }
125
126 527 static ::casadi::Matrix<Scalar> dummy_precision()
127 {
128 527 return ::casadi::Matrix<Scalar>(NumTraits<double>::dummy_precision());
129 }
130
131 static ::casadi::Matrix<Scalar> highest()
132 {
133 return ::casadi::Matrix<Scalar>(std::numeric_limits<double>::max());
134 }
135
136 static ::casadi::Matrix<Scalar> lowest()
137 {
138 return ::casadi::Matrix<Scalar>(std::numeric_limits<double>::min());
139 }
140
141 static int digits10()
142 {
143 return std::numeric_limits<double>::digits10;
144 }
145 };
146 } // namespace Eigen
147
148 namespace pinocchio
149 {
150 namespace casadi
151 {
152 // Copy casadi matrix to Eigen matrix
153 template<typename MT, typename Scalar>
154 2941 inline void copy(::casadi::Matrix<Scalar> const & src, Eigen::MatrixBase<MT> & dst)
155 {
156 2941 Eigen::DenseIndex const m = src.size1();
157 2941 Eigen::DenseIndex const n = src.size2();
158
159 2941 dst.resize(m, n);
160
161
2/2
✓ Branch 0 taken 9892 times.
✓ Branch 1 taken 1471 times.
22722 for (Eigen::DenseIndex i = 0; i < m; ++i)
162
2/2
✓ Branch 0 taken 12433 times.
✓ Branch 1 taken 9892 times.
44638 for (Eigen::DenseIndex j = 0; j < n; ++j)
163
3/6
✓ Branch 1 taken 12433 times.
✗ Branch 2 not taken.
✓ Branch 4 taken 12433 times.
✗ Branch 5 not taken.
✓ Branch 7 taken 12433 times.
✗ Branch 8 not taken.
24857 dst(i, j) = src(i, j);
164 2941 }
165
166 // Copy casadi matrix to Eigen::Tensor
167 template<typename TensorDerived, typename Scalar>
168 inline void copy(::casadi::Matrix<Scalar> const & src, Eigen::TensorBase<TensorDerived> & dst_)
169 {
170 TensorDerived & dst = static_cast<TensorDerived &>(dst_);
171 Eigen::Index const m = src.size1();
172 Eigen::Index const n = src.size2();
173 // Eigen::Index const d = 1;
174 // dst.resize(d, m, n); // TODO(jcarpent) enable the resize depending on the tensor type.
175 // Otherwise we should throw an error.
176
177 for (Eigen::Index i = 0; i < m; ++i)
178 for (Eigen::Index j = 0; j < n; ++j)
179 dst(0, i, j) = src(i, j);
180 }
181
182 // Copy Eigen matrix to casadi matrix
183 template<typename TensorDerived, typename Scalar>
184 inline void copy(Eigen::TensorBase<TensorDerived> const & _src, ::casadi::Matrix<Scalar> & dst)
185 {
186 const TensorDerived & src = static_cast<const TensorDerived &>(_src);
187 Eigen::Index const m = src.dimension(1);
188 Eigen::Index const n = src.dimension(2);
189
190 PINOCCHIO_CHECK_ARGUMENT_SIZE(src.dimension(0), 1);
191 dst.resize(m, n);
192
193 for (Eigen::Index i = 0; i < m; ++i)
194 for (Eigen::Index j = 0; j < n; ++j)
195 dst(i, j) = src(0, i, j);
196 }
197
198 // Copy Eigen matrix to casadi matrix
199 template<typename MT, typename Scalar>
200 20893 inline void copy(Eigen::MatrixBase<MT> const & src, ::casadi::Matrix<Scalar> & dst)
201 {
202 20893 Eigen::DenseIndex const m = src.rows();
203 20893 Eigen::DenseIndex const n = src.cols();
204
205 20893 dst.resize(m, n);
206
207
2/2
✓ Branch 0 taken 35011 times.
✓ Branch 1 taken 10767 times.
86665 for (Eigen::DenseIndex i = 0; i < m; ++i)
208
2/2
✓ Branch 0 taken 101514 times.
✓ Branch 1 taken 35011 times.
264550 for (Eigen::DenseIndex j = 0; j < n; ++j)
209
4/8
✓ Branch 1 taken 101514 times.
✗ Branch 2 not taken.
✓ Branch 4 taken 101514 times.
✗ Branch 5 not taken.
✓ Branch 7 taken 101514 times.
✗ Branch 8 not taken.
✓ Branch 10 taken 90012 times.
✗ Branch 11 not taken.
198778 dst(i, j) = src(i, j);
210 20893 }
211
212 // Copy Eigen sparse matrix to casadi matrix
213 template<typename MT, typename Scalar>
214 inline void copy(Eigen::SparseMatrixBase<MT> const & src, ::casadi::Matrix<Scalar> & dst)
215 {
216 Eigen::DenseIndex const m = src.rows();
217 Eigen::DenseIndex const n = src.cols();
218
219 dst.resize(m, n);
220
221 // TODO this method is not optimal
222 // (we could copy only non zero values)
223 for (Eigen::Index i = 0; i < m; ++i)
224 for (Eigen::Index j = 0; j < n; ++j)
225 dst(i, j) = src.derived().coeff(i, j);
226 }
227
228 // Make an Eigen matrix consisting of pure casadi symbolics
229 template<typename MatrixDerived>
230 1 inline void sym(const Eigen::MatrixBase<MatrixDerived> & eig_mat, std::string const & name)
231 {
232 typedef typename MatrixDerived::Scalar SX;
233
234 1 MatrixDerived & eig_mat_ = PINOCCHIO_EIGEN_CONST_CAST(MatrixDerived, eig_mat);
235
2/2
✓ Branch 1 taken 3 times.
✓ Branch 2 taken 1 times.
4 for (Eigen::DenseIndex i = 0; i < eig_mat.rows(); ++i)
236
2/2
✓ Branch 1 taken 12 times.
✓ Branch 2 taken 3 times.
15 for (Eigen::DenseIndex j = 0; j < eig_mat.cols(); ++j)
237
8/16
✓ Branch 2 taken 12 times.
✗ Branch 3 not taken.
✓ Branch 5 taken 12 times.
✗ Branch 6 not taken.
✓ Branch 8 taken 12 times.
✗ Branch 9 not taken.
✓ Branch 11 taken 12 times.
✗ Branch 12 not taken.
✓ Branch 14 taken 12 times.
✗ Branch 15 not taken.
✓ Branch 17 taken 12 times.
✗ Branch 18 not taken.
✓ Branch 20 taken 12 times.
✗ Branch 21 not taken.
✓ Branch 23 taken 12 times.
✗ Branch 24 not taken.
12 eig_mat_(i, j) = SX::sym(name + "_" + std::to_string(i) + "_" + std::to_string(j));
238 1 }
239
240 } // namespace casadi
241 } // namespace pinocchio
242
243 // Overloading of min/max operator
244 namespace pinocchio
245 {
246 namespace math
247 {
248 namespace internal
249 {
250 template<typename Scalar>
251 struct return_type_min<::casadi::Matrix<Scalar>, ::casadi::Matrix<Scalar>>
252 {
253 typedef ::casadi::Matrix<Scalar> type;
254 };
255
256 template<typename Scalar, typename T>
257 struct return_type_min<::casadi::Matrix<Scalar>, T>
258 {
259 typedef ::casadi::Matrix<Scalar> type;
260 };
261
262 template<typename Scalar, typename T>
263 struct return_type_min<T, ::casadi::Matrix<Scalar>>
264 {
265 typedef ::casadi::Matrix<Scalar> type;
266 };
267
268 template<typename Scalar>
269 struct call_min<::casadi::Matrix<Scalar>, ::casadi::Matrix<Scalar>>
270 {
271 static inline ::casadi::Matrix<Scalar>
272 run(const ::casadi::Matrix<Scalar> & a, const ::casadi::Matrix<Scalar> & b)
273 {
274 return fmin(a, b);
275 }
276 };
277
278 template<typename S1, typename S2>
279 struct call_min<::casadi::Matrix<S1>, S2>
280 {
281 typedef ::casadi::Matrix<S1> CasadiType;
282 static inline ::casadi::Matrix<S1> run(const ::casadi::Matrix<S1> & a, const S2 & b)
283 {
284 return fmin(a, static_cast<CasadiType>(b));
285 }
286 };
287
288 template<typename S1, typename S2>
289 struct call_min<S1, ::casadi::Matrix<S2>>
290 {
291 typedef ::casadi::Matrix<S2> CasadiType;
292 static inline ::casadi::Matrix<S2> run(const S1 & a, const ::casadi::Matrix<S2> & b)
293 {
294 return fmin(static_cast<CasadiType>(a), b);
295 }
296 };
297
298 template<typename Scalar>
299 struct return_type_max<::casadi::Matrix<Scalar>, ::casadi::Matrix<Scalar>>
300 {
301 typedef ::casadi::Matrix<Scalar> type;
302 };
303
304 template<typename Scalar, typename T>
305 struct return_type_max<::casadi::Matrix<Scalar>, T>
306 {
307 typedef ::casadi::Matrix<Scalar> type;
308 };
309
310 template<typename Scalar, typename T>
311 struct return_type_max<T, ::casadi::Matrix<Scalar>>
312 {
313 typedef ::casadi::Matrix<Scalar> type;
314 };
315
316 template<typename Scalar>
317 struct call_max<::casadi::Matrix<Scalar>, ::casadi::Matrix<Scalar>>
318 {
319 static inline ::casadi::Matrix<Scalar>
320 433 run(const ::casadi::Matrix<Scalar> & a, const ::casadi::Matrix<Scalar> & b)
321 {
322 433 return fmax(a, b);
323 }
324 };
325
326 template<typename S1, typename S2>
327 struct call_max<::casadi::Matrix<S1>, S2>
328 {
329 typedef ::casadi::Matrix<S1> CasadiType;
330 1 static inline ::casadi::Matrix<S1> run(const ::casadi::Matrix<S1> & a, const S2 & b)
331 {
332
1/2
✓ Branch 2 taken 1 times.
✗ Branch 3 not taken.
2 return fmax(a, static_cast<CasadiType>(b));
333 }
334 };
335
336 template<typename S1, typename S2>
337 struct call_max<S1, ::casadi::Matrix<S2>>
338 {
339 typedef ::casadi::Matrix<S2> CasadiType;
340 1 static inline ::casadi::Matrix<S2> run(const S1 & a, const ::casadi::Matrix<S2> & b)
341 {
342
1/2
✓ Branch 2 taken 1 times.
✗ Branch 3 not taken.
2 return fmax(static_cast<CasadiType>(a), b);
343 }
344 };
345 } // namespace internal
346
347 } // namespace math
348
349 } // namespace pinocchio
350
351 namespace Eigen
352 {
353
354 // Max operator
355 template<typename Scalar>
356 struct ScalarBinaryOpTraits<
357 ::casadi::Matrix<Scalar>,
358 ::casadi::Matrix<Scalar>,
359 internal::scalar_max_op<::casadi::Matrix<Scalar>, ::casadi::Matrix<Scalar>>>
360 {
361 typedef ::casadi::Matrix<Scalar> ReturnType;
362 };
363
364 template<typename S1, typename S2>
365 struct ScalarBinaryOpTraits<
366 ::casadi::Matrix<S1>,
367 S2,
368 internal::scalar_max_op<::casadi::Matrix<S1>, S2>>
369 {
370 typedef ::casadi::Matrix<S1> ReturnType;
371 };
372
373 template<typename S1, typename S2>
374 struct ScalarBinaryOpTraits<
375 S1,
376 ::casadi::Matrix<S2>,
377 internal::scalar_max_op<S1, ::casadi::Matrix<S2>>>
378 {
379 typedef ::casadi::Matrix<S1> ReturnType;
380 };
381
382 namespace internal
383 {
384
385 template<typename Scalar>
386 struct scalar_max_op<::casadi::Matrix<Scalar>, ::casadi::Matrix<Scalar>>
387 : binary_op_base<::casadi::Matrix<Scalar>, ::casadi::Matrix<Scalar>>
388 {
389 typedef ::casadi::Matrix<Scalar> LhsScalar;
390 typedef ::casadi::Matrix<Scalar> RhsScalar;
391 typedef
392 typename ScalarBinaryOpTraits<LhsScalar, RhsScalar, scalar_max_op>::ReturnType result_type;
393
394 EIGEN_EMPTY_STRUCT_CTOR(scalar_max_op)
395 EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE const result_type
396 operator()(const LhsScalar & a, const RhsScalar & b) const
397 {
398 return ::pinocchio::math::internal::call_max<LhsScalar, RhsScalar>::run(a, b);
399 }
400 // template<typename Packet>
401 // EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE const Packet packetOp(const Packet& a, const
402 // Packet& b) const { return internal::pmax(a,b); } template<typename Packet>
403 // EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE const result_type predux(const Packet& a) const
404 // { return internal::predux_max(a); }
405 };
406
407 template<typename S1, typename S2>
408 struct scalar_max_op<S1, ::casadi::Matrix<S2>> : binary_op_base<S1, ::casadi::Matrix<S2>>
409 {
410 typedef S1 LhsScalar;
411 typedef ::casadi::Matrix<S2> RhsScalar;
412 typedef
413 typename ScalarBinaryOpTraits<LhsScalar, RhsScalar, scalar_max_op>::ReturnType result_type;
414
415 EIGEN_EMPTY_STRUCT_CTOR(scalar_max_op)
416 EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE const result_type
417 operator()(const LhsScalar & a, const RhsScalar & b) const
418 {
419 return ::pinocchio::math::internal::call_max<LhsScalar, RhsScalar>::run(a, b);
420 }
421 };
422
423 template<typename S1, typename S2>
424 struct scalar_max_op<::casadi::Matrix<S1>, S2> : binary_op_base<::casadi::Matrix<S1>, S2>
425 {
426 typedef ::casadi::Matrix<S1> LhsScalar;
427 typedef S2 RhsScalar;
428 typedef
429 typename ScalarBinaryOpTraits<LhsScalar, RhsScalar, scalar_max_op>::ReturnType result_type;
430
431 EIGEN_EMPTY_STRUCT_CTOR(scalar_max_op)
432 EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE const result_type
433 operator()(const LhsScalar & a, const RhsScalar & b) const
434 {
435 return ::pinocchio::math::internal::call_max<LhsScalar, RhsScalar>::run(a, b);
436 }
437 };
438 } // namespace internal
439 } // namespace Eigen
440
441 #include "pinocchio/autodiff/casadi/spatial/se3-tpl.hpp"
442 #include "pinocchio/autodiff/casadi/utils/static-if.hpp"
443 #include "pinocchio/autodiff/casadi/math/matrix.hpp"
444 #include "pinocchio/autodiff/casadi/math/quaternion.hpp"
445 #include "pinocchio/autodiff/casadi/math/triangular-matrix.hpp"
446
447 #endif // #ifndef __pinocchio_autodiff_casadi_hpp__
448