12 #include <boost/test/unit_test.hpp>
13 #include <boost/utility/binary.hpp>
15 BOOST_AUTO_TEST_SUITE(BOOST_TEST_MODULE)
19 typedef casadi::SX AD_double;
29 typedef Eigen::Matrix<AD_double, Eigen::Dynamic, 1> VectorXAD;
30 typedef Eigen::Matrix<AD_double, 6, 1> Vector6AD;
33 typedef JointModelRXAD::ConfigVector_t ConfigVectorAD;
38 typedef JointModelRX::ConfigVector_t ConfigVector;
39 typedef JointModelRX::TangentVector_t TangentVector;
43 jmodel.setIndexes(0, 0, 0);
46 JointModelRXAD jmodel_ad = jmodel.cast<AD_double>();
47 JointDataRXAD jdata_ad(jmodel_ad.createData());
50 ConfigVector
q(jmodel.nq());
51 JointOperation().random(
q);
54 ConfigVectorAD q_ad(jmodel.nq());
55 for (Eigen::DenseIndex k = 0; k < jmodel.nq(); ++k)
61 jmodel_ad.calc(jdata_ad, q_ad);
62 jmodel.calc(jdata,
q);
67 casadi::SX cs_trans(3, 1);
68 for (Eigen::DenseIndex k = 0; k < 3; ++k)
70 cs_trans(k) = M2.translation()[k];
72 casadi::SX cs_rot(3, 3);
73 for (Eigen::DenseIndex
i = 0;
i < 3; ++
i)
75 for (Eigen::DenseIndex j = 0; j < 3; ++j)
77 cs_rot(
i, j) = M2.rotation()(
i, j);
81 casadi::Function eval_placement(
82 "eval_placement", casadi::SXVector{cs_q}, casadi::SXVector{cs_trans, cs_rot});
83 std::cout <<
"Joint Placement = " << eval_placement << std::endl;
85 std::vector<double> q_vec((
size_t)jmodel.nq());
86 Eigen::Map<ConfigVector>(q_vec.data(), jmodel.nq(), 1) =
q;
87 casadi::DMVector
res = eval_placement(casadi::DMVector{q_vec});
88 std::cout <<
"M(q)=" <<
res << std::endl;
90 BOOST_CHECK(M1.translation().isApprox(Eigen::Map<SE3::Vector3>(
res[0]->data())));
91 BOOST_CHECK(M1.rotation().isApprox(Eigen::Map<SE3::Matrix3>(
res[1]->data())));
95 TangentVector
v(TangentVector::Random(jmodel.nv()));
96 VectorXAD v_ad(jmodel_ad.nv());
98 std::vector<double> v_vec((
size_t)jmodel.nv());
99 Eigen::Map<TangentVector>(v_vec.data(), jmodel.nv(), 1) =
v;
101 for (Eigen::DenseIndex k = 0; k < jmodel.nv(); ++k)
106 jmodel.calc(jdata,
q,
v);
110 jmodel_ad.calc(jdata_ad, q_ad, v_ad);
112 MotionAD m_ad(jdata_ad.v);
114 casadi::SX cs_vel(6, 1);
115 for (Eigen::DenseIndex k = 0; k < 6; ++k)
117 cs_vel(k) = m_ad.toVector()[k];
119 casadi::Function eval_velocity(
120 "eval_velocity", casadi::SXVector{cs_q, cs_v}, casadi::SXVector{cs_vel});
121 std::cout <<
"Joint Velocity = " << eval_velocity << std::endl;
123 casadi::DMVector res_vel = eval_velocity(casadi::DMVector{q_vec, v_vec});
124 std::cout <<
"v(q,v)=" << res_vel << std::endl;
126 BOOST_CHECK(
m.linear().isApprox(Eigen::Map<Motion::Vector3>(res_vel[0]->data())));
127 BOOST_CHECK(
m.angular().isApprox(Eigen::Map<Motion::Vector3>(res_vel[0]->data() + 3)));
129 casadi::SX dvel_dv =
jacobian(cs_vel, cs_v);
130 casadi::Function eval_S(
"eval_S", casadi::SXVector{cs_q, cs_v}, casadi::SXVector{dvel_dv});
131 std::cout <<
"S = " << eval_S << std::endl;
133 casadi::DMVector res_S = eval_S(casadi::DMVector{q_vec, v_vec});
134 std::cout <<
"res_S:" << res_S << std::endl;
135 JointMotionSubspaceXd::DenseBase Sref_mat = Sref.matrix();
137 for (Eigen::DenseIndex
i = 0;
i < 6; ++
i)
139 for (Eigen::DenseIndex j = 0;
i < Sref.nv(); ++
i)
141 std::fabs(Sref_mat(
i, j) - (
double)res_S[0](
i, j))
142 <= Eigen::NumTraits<double>::dummy_precision());
146 template<
typename Jo
intModel_>
149 template<
typename Jo
intModel_>
155 jmodel.setIndexes(0, 0, 0);
161 return "default " + JointModel_::classname();
165 template<
typename Scalar,
int Options>
166 struct init<
pinocchio::JointModelRevoluteUnalignedTpl<Scalar, Options>>
173 JointModel jmodel(Vector3::Random().normalized());
181 return JointModel::classname();
185 template<
typename Scalar,
int Options>
186 struct init<
pinocchio::JointModelRevoluteUnboundedUnalignedTpl<Scalar, Options>>
193 JointModel jmodel(Vector3::Random().normalized());
201 return JointModel::classname();
205 template<
typename Scalar,
int Options>
206 struct init<
pinocchio::JointModelPrismaticUnalignedTpl<Scalar, Options>>
213 JointModel jmodel(Vector3::Random().normalized());
221 return JointModel::classname();
225 template<
typename Scalar,
int Options,
template<
typename,
int>
class JointCollection>
226 struct init<
pinocchio::JointModelTpl<Scalar, Options, JointCollection>>
241 return JointModel::classname();
245 template<
typename Scalar,
int Options,
template<
typename,
int>
class JointCollection>
246 struct init<
pinocchio::JointModelCompositeTpl<Scalar, Options, JointCollection>>
257 jmodel.setIndexes(0, 0, 0);
263 return JointModel::classname();
267 template<
typename Jo
intModel_>
283 return JointModel::classname();
289 template<
typename Jo
intModel_>
293 jmodel.setIndexes(0, 0, 0);
297 template<
typename Scalar,
int Options,
int axis>
302 jmodel.setIndexes(0, 0, 0);
307 template<
typename Scalar,
int Options>
312 JointModel jmodel(Vector3::UnitX(), Vector3::UnitY());
313 jmodel.setIndexes(0, 0, 0);
318 template<
typename Scalar,
int Options>
323 JointModel jmodel(Vector3::Random().normalized());
324 jmodel.setIndexes(0, 0, 0);
329 template<
typename Scalar,
int Options>
334 JointModel jmodel(Vector3::Random().normalized());
335 jmodel.setIndexes(0, 0, 0);
340 template<
typename Scalar,
int Options>
345 JointModel jmodel(Vector3::Random().normalized());
346 jmodel.setIndexes(0, 0, 0);
351 template<
typename Scalar,
int Options>
356 JointModel jmodel(Vector3::Random().normalized());
357 jmodel.setIndexes(0, 0, 0);
362 template<
typename Scalar,
int Options,
template<
typename,
int>
class JointCollection>
368 jmodel.setIndexes(0, 0, 0);
373 template<
typename Scalar,
int Options,
template<
typename,
int>
class JointCollection>
381 jmodel.setIndexes(0, 0, 0);
387 template<
typename Jo
intModel_>
392 template<
typename Jo
intModel>
395 std::cout <<
"--" << std::endl;
396 std::cout <<
"jmodel: " << jmodel.
shortname() << std::endl;
398 typedef casadi::SX AD_double;
406 typedef Eigen::Matrix<AD_double, Eigen::Dynamic, 1> VectorXAD;
407 typedef Eigen::Matrix<AD_double, 6, 1> Vector6AD;
410 typedef typename JointModelAD::JointDataDerived JointDataAD;
412 typedef typename JointModelAD::ConfigVector_t ConfigVectorAD;
414 typedef typename JointModel::JointDataDerived
JointData;
415 typedef typename JointModel::ConfigVector_t ConfigVector;
416 typedef typename JointModel::TangentVector_t TangentVector;
421 JointModelAD jmodel_ad = jmodel.template cast<AD_double>();
422 JointDataAD jdata_ad(jmodel_ad.createData());
425 ConfigVector
q(jmodel.
nq());
427 ConfigVector lb(ConfigVector::Constant(jmodel.
nq(), -1.));
428 ConfigVector ub(ConfigVector::Constant(jmodel.
nq(), 1.));
430 typedef pinocchio::RandomConfigurationStep<
436 ConfigVectorAD q_ad(jmodel.
nq());
437 for (Eigen::DenseIndex k = 0; k < jmodel.
nq(); ++k)
443 jmodel_ad.calc(jdata_ad, q_ad);
444 jmodel.
calc(jdata,
q);
446 SE3 M1(jdata_base.
M());
447 SE3AD M2(jdata_ad_base.
M());
449 casadi::SX cs_trans(3, 1);
450 for (Eigen::DenseIndex k = 0; k < 3; ++k)
452 cs_trans(k) = M2.translation()[k];
454 casadi::SX cs_rot(3, 3);
455 for (Eigen::DenseIndex
i = 0;
i < 3; ++
i)
457 for (Eigen::DenseIndex j = 0; j < 3; ++j)
459 cs_rot(
i, j) = M2.rotation()(
i, j);
463 casadi::Function eval_placement(
464 "eval_placement", casadi::SXVector{cs_q}, casadi::SXVector{cs_trans, cs_rot});
465 std::cout <<
"Joint Placement = " << eval_placement << std::endl;
467 std::vector<double> q_vec((
size_t)jmodel.
nq());
468 Eigen::Map<ConfigVector>(q_vec.data(), jmodel.
nq(), 1) =
q;
469 casadi::DMVector
res = eval_placement(casadi::DMVector{q_vec});
470 std::cout <<
"M(q)=" <<
res << std::endl;
472 BOOST_CHECK(M1.translation().isApprox(Eigen::Map<SE3::Vector3>(
res[0]->data())));
473 BOOST_CHECK(M1.rotation().isApprox(Eigen::Map<SE3::Matrix3>(
res[1]->data())));
477 TangentVector
v(TangentVector::Random(jmodel.
nv()));
478 VectorXAD v_ad(jmodel_ad.nv());
480 std::vector<double> v_vec((
size_t)jmodel.
nv());
481 Eigen::Map<TangentVector>(v_vec.data(), jmodel.
nv(), 1) =
v;
483 for (Eigen::DenseIndex k = 0; k < jmodel.
nv(); ++k)
492 jmodel_ad.calc(jdata_ad, q_ad, v_ad);
494 MotionAD m_ad(jdata_ad_base.
v());
496 casadi::SX cs_vel(6, 1);
497 for (Eigen::DenseIndex k = 0; k < 6; ++k)
499 cs_vel(k) = m_ad.toVector()[k];
501 casadi::Function eval_velocity(
502 "eval_velocity", casadi::SXVector{cs_q, cs_v}, casadi::SXVector{cs_vel});
503 std::cout <<
"Joint Velocity = " << eval_velocity << std::endl;
505 casadi::DMVector res_vel = eval_velocity(casadi::DMVector{q_vec, v_vec});
506 std::cout <<
"v(q,v)=" << res_vel << std::endl;
508 BOOST_CHECK(
m.linear().isApprox(Eigen::Map<Motion::Vector3>(res_vel[0]->data())));
509 BOOST_CHECK(
m.angular().isApprox(Eigen::Map<Motion::Vector3>(res_vel[0]->data() + 3)));
511 casadi::SX dvel_dv =
jacobian(cs_vel, cs_v);
512 casadi::Function eval_S(
"eval_S", casadi::SXVector{cs_q, cs_v}, casadi::SXVector{dvel_dv});
513 std::cout <<
"S = " << eval_S << std::endl;
515 casadi::DMVector res_S = eval_S(casadi::DMVector{q_vec, v_vec});
516 std::cout <<
"res_S:" << res_S << std::endl;
517 JointMotionSubspaceXd::DenseBase Sref_mat = Sref.matrix();
519 for (Eigen::DenseIndex
i = 0;
i < 6; ++
i)
521 for (Eigen::DenseIndex j = 0;
i < Sref.nv(); ++
i)
523 std::fabs(Sref_mat(
i, j) - (
double)res_S[0](
i, j))
524 <= Eigen::NumTraits<double>::dummy_precision());
527 std::cout <<
"--" << std::endl << std::endl;
539 BOOST_AUTO_TEST_SUITE_END()