5 #include <pinocchio/autodiff/casadi.hpp> 7 #include <pinocchio/math/quaternion.hpp> 8 #include <pinocchio/spatial/se3.hpp> 9 #include <pinocchio/spatial/motion.hpp> 11 #include <boost/variant.hpp> 13 #include <boost/test/unit_test.hpp> 14 #include <boost/utility/binary.hpp> 16 BOOST_AUTO_TEST_SUITE(BOOST_TEST_MODULE)
21 SE3 M1 = SE3::Identity();
22 SE3 M2 = SE3::Random();
25 SE3 M1inv = M1.inverse();
31 Motion v1 = Motion::Zero();
32 Motion v2 = Motion::Random();
43 SE3AD::Matrix3 & ad_rot = ad_M.
rotation();
48 SE3AD::Quaternion ad_quat;
51 casadi::SX cs_quat(4,1);
54 casadi::Function eval_quat(
"eval_quat",
55 casadi::SXVector {cs_rot},
56 casadi::SXVector {cs_quat});
59 for(
int k = 0; k < 1e4; ++k)
62 SE3::Quaternion quat_ref(M.rotation());
64 casadi::DM vec_rot(3,3);
67 casadi::DM quat_res = eval_quat(casadi::DMVector {vec_rot})[0];
68 SE3::Quaternion quat_value;
70 quat_value.coeffs() = Eigen::Map<Eigen::Vector4d>(
static_cast< std::vector<double>
>(quat_res).
data());
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)
void assignQuaternion(Eigen::QuaternionBase< D > &quat, const Eigen::MatrixBase< Matrix3 > &R)
void copy(::casadi::Matrix< Scalar > const &src, Eigen::MatrixBase< MT > &dst)
ConstAngularRef rotation() const