casadi/spatial.cpp
Go to the documentation of this file.
1 //
2 // Copyright (c) 2019 INRIA
3 //
4 
6 
11 
13 
14 #include <boost/variant.hpp> // to avoid C99 warnings
15 
16 #include <iostream>
17 #include <boost/test/unit_test.hpp>
18 #include <boost/utility/binary.hpp>
19 
20 BOOST_AUTO_TEST_SUITE(BOOST_TEST_MODULE)
21 
23 {
25  SE3 M1 = SE3::Identity();
26  SE3 M2 = SE3::Random();
27 
28  SE3 M3 = M2 * M1;
29  SE3 M1inv = M1.inverse();
30 
31  ::casadi::SX trans;
32  pinocchio::casadi::copy(M1.translation(), trans);
33 
34  const Eigen::DenseIndex col = 0;
35  for (Eigen::DenseIndex k = 0; k < 3; ++k)
36  {
37  BOOST_CHECK(casadi::SX::is_equal(trans(k, col), M1.translation()[k]));
38  }
39 }
40 
42 {
44  Motion v1 = Motion::Zero();
45  Motion v2 = Motion::Random();
46 
47  Motion v3 = v1 + v2;
48 }
49 
50 BOOST_AUTO_TEST_CASE(test_quaternion)
51 {
52  typedef pinocchio::SE3Tpl<casadi::SX> SE3AD;
53  typedef pinocchio::SE3 SE3;
54 
55  SE3AD ad_M;
56  SE3AD::Matrix3 & ad_rot = ad_M.rotation();
57 
58  casadi::SX cs_rot = casadi::SX::sym("rot", 3, 3);
59  pinocchio::casadi::copy(cs_rot, ad_rot);
60 
61  SE3AD::Quaternion ad_quat;
63 
64  casadi::SX cs_quat(4, 1);
65  pinocchio::casadi::copy(ad_quat.coeffs(), cs_quat);
66 
67  casadi::Function eval_quat("eval_quat", casadi::SXVector{cs_rot}, casadi::SXVector{cs_quat});
68 
69  for (int k = 0; k < 1e4; ++k)
70  {
71  SE3 M(SE3::Random());
72  SE3::Quaternion quat_ref(M.rotation());
73 
74  casadi::DM vec_rot(3, 3);
75  pinocchio::casadi::copy(M.rotation(), vec_rot);
76 
77  casadi::DM quat_res = eval_quat(casadi::DMVector{vec_rot})[0];
78  SE3::Quaternion quat_value;
79 
80  quat_value.coeffs() =
81  Eigen::Map<Eigen::Vector4d>(static_cast<std::vector<double>>(quat_res).data());
82  BOOST_CHECK(pinocchio::quaternion::defineSameRotation(quat_value, quat_ref));
83  // if(! quat_value.coeffs().isApprox(quat_ref.coeffs()))
84  // {
85  // std::cout << "quat_value: " << quat_value.coeffs().transpose() << std::endl;
86  // std::cout << "quat_ref: " << quat_ref.coeffs().transpose() << std::endl;
87  // }
88  }
89 }
90 
91 BOOST_AUTO_TEST_CASE(test_log3_firstorder_derivatives)
92 {
93  typedef double Scalar;
94  typedef casadi::SX ADScalar;
95 
96  typedef pinocchio::SE3 SE3;
97  typedef SE3::Vector3 Vector3;
98  typedef SE3::Matrix3 Matrix3;
99 
100  typedef pinocchio::SE3Tpl<ADScalar> SE3AD;
101  typedef SE3AD::Vector3 Vector3AD;
102  typedef SE3AD::Matrix3 Matrix3AD;
103 
104  SE3::Matrix3 RTarget;
105  pinocchio::toRotationMatrix(Vector3(SE3::Vector3::UnitX()), pinocchio::PI<Scalar>() / 4, RTarget);
106 
107  SE3::Quaternion quat0(0.707107, 0.707107, 0, 0);
108  Matrix3 R0 = quat0.toRotationMatrix();
109  Vector3 nu0 = pinocchio::log3(R0);
110 
111  casadi::SX cs_nu = casadi::SX::sym("nu", 3);
112 
113  Vector3AD nu_ad = Eigen::Map<Vector3AD>(static_cast<std::vector<ADScalar>>(cs_nu).data());
114  auto log3_casadi_exp =
115  pinocchio::log3(pinocchio::exp3(nu_ad).transpose() * RTarget.cast<ADScalar>());
116 
117  casadi::SX cs_res = casadi::SX::sym("res", 3);
118  pinocchio::casadi::copy(log3_casadi_exp, cs_res);
119 
120  casadi::Function log3_casadi("log3_casadi", casadi::SXVector{cs_nu}, casadi::SXVector{cs_res});
121 
122  std::vector<double> log3_casadi_input(3);
123  Eigen::Map<Vector3>(log3_casadi_input.data()) = nu0;
124  casadi::DM log3_casadi_res = log3_casadi(casadi::DMVector{log3_casadi_input})[0];
125  Vector3 res0 = Eigen::Map<Vector3>(static_cast<std::vector<double>>(log3_casadi_res).data());
126 
127  Vector3 res0_ref = pinocchio::log3(pinocchio::exp3(nu0).transpose() * RTarget);
128 
129  // Check first that the value matches
130  BOOST_CHECK(res0 == res0);
131  BOOST_CHECK(res0_ref == res0_ref);
132  BOOST_CHECK(res0.isApprox(res0_ref));
133 
134  ADScalar log3_casadi_jacobian_exp = jacobian(cs_res, cs_nu);
135  casadi::Function log3_casadi_jacobian(
136  "log3_casadi_jacobian", casadi::SXVector{cs_nu}, casadi::SXVector{log3_casadi_jacobian_exp});
137 
138  casadi::DM log3_casadi_jacobian_res =
139  log3_casadi_jacobian(casadi::DMVector{log3_casadi_input})[0];
140  Matrix3 jac0 =
141  Eigen::Map<Matrix3>(static_cast<std::vector<double>>(log3_casadi_jacobian_res).data());
142 
143  BOOST_CHECK(jac0 == jac0);
144 
145  ADScalar log3_casadi_gradient_exp = gradient(log3_casadi_exp[0], cs_nu);
146 
147  casadi::Function log3_casadi_gradient(
148  "log3_casadi_jacobian", casadi::SXVector{cs_nu}, casadi::SXVector{log3_casadi_gradient_exp});
149 
150  casadi::DM log3_casadi_gradient_res =
151  log3_casadi_gradient(casadi::DMVector{log3_casadi_input})[0];
152  Vector3 grad0 =
153  Eigen::Map<Vector3>(static_cast<std::vector<double>>(log3_casadi_gradient_res).data());
154 
155  BOOST_CHECK(grad0 == grad0);
156 }
157 
158 BOOST_AUTO_TEST_SUITE_END()
quaternion.hpp
pinocchio::SE3Tpl::inverse
SE3Tpl inverse() const
aXb = bXa.inverse()
Definition: spatial/se3-tpl.hpp:149
pinocchio.casadi::sym
void sym(const Eigen::MatrixBase< MatrixDerived > &eig_mat, std::string const &name)
Definition: autodiff/casadi.hpp:230
pinocchio::SE3Tpl
Definition: context/casadi.hpp:29
setup.data
data
Definition: cmake/cython/setup.in.py:48
pinocchio::python::Scalar
context::Scalar Scalar
Definition: admm-solver.cpp:29
pinocchio::exp3
Eigen::Matrix< typename Vector3Like::Scalar, 3, 3, PINOCCHIO_EIGEN_PLAIN_TYPE(Vector3Like)::Options > exp3(const Eigen::MatrixBase< Vector3Like > &v)
Exp: so3 -> SO3.
Definition: spatial/explog.hpp:36
explog.hpp
pinocchio::python::context::Motion
MotionTpl< Scalar, Options > Motion
Definition: bindings/python/context/generic.hpp:54
motion.hpp
pinocchio::quaternion::assignQuaternion
void assignQuaternion(Eigen::QuaternionBase< D > &quat, const Eigen::MatrixBase< Matrix3 > &R)
Definition: math/quaternion.hpp:214
pinocchio::python::context::Quaternion
Eigen::Quaternion< Scalar, Options > Quaternion
Definition: bindings/python/context/generic.hpp:49
se3.hpp
pinocchio::SE3Tpl::rotation
ConstAngularRef rotation() const
Definition: se3-base.hpp:48
M
M
pinocchio::context::Vector3
Eigen::Matrix< Scalar, 3, 1, Options > Vector3
Definition: context/generic.hpp:53
pinocchio::jacobian
void jacobian(const ConstraintModelTpl< Scalar, Options, ConstraintCollectionTpl > &cmodel, ConstraintDataTpl< Scalar, Options, ConstraintCollectionTpl > &cdata, const ModelTpl< Scalar, Options, JointCollectionTpl > &model, const DataTpl< Scalar, Options, JointCollectionTpl > &data, const Eigen::MatrixBase< JacobianMatrix > &jacobian_matrix)
Definition: constraint-model-visitor.hpp:199
pinocchio::quaternion::defineSameRotation
bool defineSameRotation(const Eigen::QuaternionBase< D1 > &q1, const Eigen::QuaternionBase< D2 > &q2, const typename D1::RealScalar &prec=Eigen::NumTraits< typename D1::Scalar >::dummy_precision())
Check if two quaternions define the same rotations.
Definition: math/quaternion.hpp:57
pinocchio::toRotationMatrix
void toRotationMatrix(const Eigen::MatrixBase< Vector3 > &axis, const Scalar &cos_value, const Scalar &sin_value, const Eigen::MatrixBase< Matrix3 > &res)
Computes a rotation matrix from a vector and values of sin and cos orientations values.
Definition: rotation.hpp:26
pinocchio.casadi::copy
void copy(::casadi::Matrix< Scalar > const &src, Eigen::MatrixBase< MT > &dst)
Definition: autodiff/casadi.hpp:154
casadi.hpp
pinocchio::log3
Eigen::Matrix< typename Matrix3Like::Scalar, 3, 1, PINOCCHIO_EIGEN_PLAIN_TYPE(Matrix3Like)::Options > log3(const Eigen::MatrixBase< Matrix3Like > &R, typename Matrix3Like::Scalar &theta)
Same as log3.
Definition: spatial/explog.hpp:83
BOOST_AUTO_TEST_CASE
BOOST_AUTO_TEST_CASE(test_se3)
Definition: casadi/spatial.cpp:22
pinocchio::python::context::SE3
SE3Tpl< Scalar, Options > SE3
Definition: bindings/python/context/generic.hpp:53
pinocchio::MotionTpl
Definition: context/casadi.hpp:27


pinocchio
Author(s):
autogenerated on Sun Dec 22 2024 03:41:12