casadi-spatial.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 <pinocchio/math/quaternion.hpp>
8 #include <pinocchio/spatial/se3.hpp>
9 #include <pinocchio/spatial/motion.hpp>
10 
11 #include <boost/variant.hpp> // to avoid C99 warnings
12 
13 #include <boost/test/unit_test.hpp>
14 #include <boost/utility/binary.hpp>
15 
16 BOOST_AUTO_TEST_SUITE(BOOST_TEST_MODULE)
17 
19 {
21  SE3 M1 = SE3::Identity();
22  SE3 M2 = SE3::Random();
23 
24  SE3 M3 = M2 * M1;
25  SE3 M1inv = M1.inverse();
26 }
27 
29 {
31  Motion v1 = Motion::Zero();
32  Motion v2 = Motion::Random();
33 
34  Motion v3 = v1 + v2;
35 }
36 
37 BOOST_AUTO_TEST_CASE(test_quaternion)
38 {
39  typedef pinocchio::SE3Tpl<casadi::SX> SE3AD;
40  typedef pinocchio::SE3 SE3;
41 
42  SE3AD ad_M;
43  SE3AD::Matrix3 & ad_rot = ad_M.rotation();
44 
45  casadi::SX cs_rot = casadi::SX::sym("rot", 3,3);
46  pinocchio::casadi::copy(cs_rot,ad_rot);
47 
48  SE3AD::Quaternion ad_quat;
50 
51  casadi::SX cs_quat(4,1);
52  pinocchio::casadi::copy(ad_quat.coeffs(),cs_quat);
53 
54  casadi::Function eval_quat("eval_quat",
55  casadi::SXVector {cs_rot},
56  casadi::SXVector {cs_quat});
57 
58 
59  for(int k = 0; k < 1e4; ++k)
60  {
61  SE3 M(SE3::Random());
62  SE3::Quaternion quat_ref(M.rotation());
63 
64  casadi::DM vec_rot(3,3);
65  pinocchio::casadi::copy(M.rotation(),vec_rot);
66 
67  casadi::DM quat_res = eval_quat(casadi::DMVector {vec_rot})[0];
68  SE3::Quaternion quat_value;
69 
70  quat_value.coeffs() = Eigen::Map<Eigen::Vector4d>(static_cast< std::vector<double> >(quat_res).data());
71  BOOST_CHECK(pinocchio::quaternion::defineSameRotation(quat_value,quat_ref));
72 // if(! quat_value.coeffs().isApprox(quat_ref.coeffs()))
73 // {
74 // std::cout << "quat_value: " << quat_value.coeffs().transpose() << std::endl;
75 // std::cout << "quat_ref: " << quat_ref.coeffs().transpose() << std::endl;
76 // }
77  }
78 
79 
80 }
81 
82 BOOST_AUTO_TEST_SUITE_END()
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.
void sym(const Eigen::MatrixBase< MatrixDerived > &eig_mat, std::string const &name)
MotionTpl< double, 0 > Motion
BOOST_AUTO_TEST_CASE(test_se3)
ConstAngularRef rotation() const
Definition: se3-base.hpp:37
void assignQuaternion(Eigen::QuaternionBase< D > &quat, const Eigen::MatrixBase< Matrix3 > &R)
M
void copy(::casadi::Matrix< Scalar > const &src, Eigen::MatrixBase< MT > &dst)
SE3Tpl< double, 0 > SE3


pinocchio
Author(s):
autogenerated on Fri Jun 23 2023 02:38:29