casadi-basic.cpp
Go to the documentation of this file.
1 //
2 // Copyright (c) 2019 INRIA
3 //
4 
5 #include <pinocchio/autodiff/casadi.hpp>
6 
7 #include <boost/variant.hpp> // to avoid C99 warnings
8 
9 #include <boost/test/unit_test.hpp>
10 #include <boost/utility/binary.hpp>
11 
12 BOOST_AUTO_TEST_SUITE(BOOST_TEST_MODULE)
13 
15 {
16  Eigen::Matrix<casadi::SX, 3, 3> A, B;
17  Eigen::Matrix<casadi::SX, 3, 1> a, b;
18  Eigen::Matrix<casadi::SX, 3, 1> c = A * a - B.transpose() * b;
19 }
20 
21 // A function working with Eigen::Matrix'es parameterized by the Scalar type
22 template <typename Scalar, typename T1, typename T2, typename T3, typename T4>
23 Eigen::Matrix<Scalar, Eigen::Dynamic, 1>
24 eigenFun(Eigen::MatrixBase<T1> const& A,
25  Eigen::MatrixBase<T2> const& a,
26  Eigen::MatrixBase<T3> const& B,
27  Eigen::MatrixBase<T4> const& b)
28 {
29  Eigen::Matrix<Scalar, Eigen::Dynamic, 1> c(4);
30  c.segment(1, 3) = A * a.segment(1, 3) - B.transpose() * b;
31  c[0] = 0.;
32 
33  return c;
34 }
35 
36 BOOST_AUTO_TEST_CASE(test_example)
37 {
38  // Declare casadi symbolic matrix arguments
39  casadi::SX cs_a = casadi::SX::sym("a", 4);
40  casadi::SX cs_b = casadi::SX::sym("b", 3);
41 
42  // Declare Eigen matrices
43  Eigen::Matrix<casadi::SX, 3, 3> A, B;
44  Eigen::Matrix<casadi::SX, -1, 1> a (4), c (4);
45  Eigen::Matrix<casadi::SX, 3, 1> b;
46 
47  // Let A, B be some numeric matrices
48  for (Eigen::Index i = 0; i < A.rows(); ++i)
49  {
50  for (Eigen::Index j = 0; j < A.cols(); ++j)
51  {
52  A(i, j) = 10. * static_cast<double>(i) + static_cast<double>(j);
53  B(i, j) = -10. * static_cast<double>(i) - static_cast<double>(j);
54  }
55  }
56 
57  // Let a, b be symbolic arguments of a function
58  pinocchio::casadi::copy(cs_b, b);
60 
61  // Call the function taking Eigen matrices
62  c = eigenFun<casadi::SX>(A, a, B, b);
63 
64  // Copy the result from Eigen matrices to casadi matrix
65  casadi::SX cs_c = casadi::SX(casadi::Sparsity::dense(c.rows(), 1));
66  pinocchio::casadi::copy(c, cs_c);
67 
68  // Display the resulting casadi matrix
69  std::cout << "c = " << cs_c << std::endl;
70 
71  // Do some AD
72  casadi::SX dc_da = jacobian(cs_c, cs_a);
73 
74  // Display the resulting jacobian
75  std::cout << "dc/da = " << dc_da << std::endl;
76 
77  // Create a function which takes a, b and returns c and dc_da
78  casadi::Function fun("fun", casadi::SXVector {cs_a, cs_b}, casadi::SXVector {cs_c, dc_da});
79  std::cout << "fun = " << fun << std::endl;
80 
81  // Evaluate the function
82  casadi::DMVector res = fun(casadi::DMVector {std::vector<double> {1., 2., 3., 4.}, std::vector<double> {-1., -2., -3.}});
83  std::cout << "fun(a, b)=" << res << std::endl;
84 }
85 
86 BOOST_AUTO_TEST_CASE(test_jacobian)
87 {
88  casadi::SX cs_x = casadi::SX::sym("x", 3);
89 
90  casadi::SX cs_y = casadi::SX::sym("y", 1);
91  cs_y(0) = cs_x(0) + cs_x(1) + cs_x(2);
92 
93  // Display the resulting expression
94  std::cout << "y = " << cs_y << std::endl;
95 
96  // Do some AD
97  casadi::SX dy_dx = jacobian(cs_x, cs_x);
98 
99  // Display the resulting jacobian
100  std::cout << "dy/dx = " << dy_dx << std::endl;
101 }
102 
103 BOOST_AUTO_TEST_CASE(test_copy_casadi_to_eigen)
104 {
105  casadi::SX cs_mat = casadi::SX::sym("A", 3, 4);
106  Eigen::Matrix<casadi::SX, 3, 4> eig_mat;
107 
108  pinocchio::casadi::copy(cs_mat, eig_mat);
109  std::cout << eig_mat << std::endl;
110 }
111 
112 BOOST_AUTO_TEST_CASE(test_copy_eigen_to_casadi)
113 {
114  Eigen::Matrix<casadi::SX, 3, 4> eig_mat;
115  pinocchio::casadi::sym(eig_mat, "A");
116 
117  casadi::SX cs_mat;
118 
119  pinocchio::casadi::copy(eig_mat, cs_mat);
120  std::cout << cs_mat << std::endl;
121 }
122 
123 BOOST_AUTO_TEST_CASE(test_casadi_codegen)
124 {
125  casadi::SX x = casadi::SX::sym("x");
126  casadi::SX y = casadi::SX::sym("y");
127  casadi::Function fun("fun", casadi::SXVector {x, y}, casadi::SXVector {x + y});
128 
129  casadi::CodeGenerator gen("module");
130  gen.add(fun);
131 
132  std::cout << gen.dump();
133 }
134 
136 {
137  casadi::SX x = casadi::SX::sym("x");
138  casadi::SX y = casadi::SX::sym("y");
139 
140  casadi::SX max_x_y = pinocchio::math::max(x,y);
141  casadi::SX max_x_0 = pinocchio::math::max(x,0.);
142  casadi::SX max_0_y = pinocchio::math::max(0.,y);
143 }
144 
145 
146 BOOST_AUTO_TEST_SUITE_END()
c
Definition: ocp.py:61
AD< Scalar > max(const AD< Scalar > &x, const AD< Scalar > &y)
void sym(const Eigen::MatrixBase< MatrixDerived > &eig_mat, std::string const &name)
Eigen::Matrix< Scalar, Eigen::Dynamic, 1 > eigenFun(Eigen::MatrixBase< T1 > const &A, Eigen::MatrixBase< T2 > const &a, Eigen::MatrixBase< T3 > const &B, Eigen::MatrixBase< T4 > const &b)
BOOST_AUTO_TEST_CASE(test_eigen)
res
std::size_t Index
list a
x
— Training
Definition: continuous.py:157
A
void copy(::casadi::Matrix< Scalar > const &src, Eigen::MatrixBase< MT > &dst)


pinocchio
Author(s):
autogenerated on Tue Jun 1 2021 02:45:02