14 #include <boost/test/unit_test.hpp>
15 #include <boost/utility/binary.hpp>
19 template<
typename Jo
intModel>
24 typedef typename JointModel::JointDataDerived
JointData;
26 std::cout <<
"Testing Joint over " << jmodel.
shortname() << std::endl;
28 Eigen::VectorXd
q1,
q2;
29 Eigen::VectorXd armature =
30 Eigen::VectorXd::Random(jdata.
S().nv()) + Eigen::VectorXd::Ones(jdata.
S().nv());
32 q1 = LieGroupType().random();
33 q2 = LieGroupType().random();
35 Eigen::VectorXd v1(Eigen::VectorXd::Random(jdata.
S().nv())),
36 v2(Eigen::VectorXd::Random(jdata.
S().nv()));
40 bool update_I =
false;
46 BOOST_CHECK(jmodel == jma);
47 BOOST_CHECK(jma == jmodel);
51 BOOST_CHECK(jda == jdata);
52 BOOST_CHECK(jdata == jda);
55 jma.
calc_aba(jda, armature, Ia, update_I);
58 jma.
calc(jda_other,
q2, v2);
59 jma.
calc_aba(jda_other, armature, Ia2, update_I);
61 BOOST_CHECK(jda_other != jda);
62 BOOST_CHECK(jda != jda_other);
63 BOOST_CHECK(jda_other != jdata);
64 BOOST_CHECK(jdata != jda_other);
66 const std::string error_prefix(
"JointModel on " + jma.
shortname());
67 BOOST_CHECK_MESSAGE(jmodel.
nq() == jma.nq(), std::string(error_prefix +
" - nq "));
68 BOOST_CHECK_MESSAGE(jmodel.
nv() == jma.nv(), std::string(error_prefix +
" - nv "));
70 BOOST_CHECK_MESSAGE(jmodel.
idx_q() == jma.idx_q(), std::string(error_prefix +
" - Idx_q "));
71 BOOST_CHECK_MESSAGE(jmodel.
idx_v() == jma.idx_v(), std::string(error_prefix +
" - Idx_v "));
72 BOOST_CHECK_MESSAGE(jmodel.
id() == jma.id(), std::string(error_prefix +
" - JointId "));
75 jda.
S().matrix().isApprox(jdata.
S().matrix()),
76 std::string(error_prefix +
" - JointMotionSubspaceXd "));
78 (jda.
M()).isApprox((jdata.
M())),
79 std::string(error_prefix +
" - Joint transforms "));
82 std::string(error_prefix +
" - Joint motions "));
83 BOOST_CHECK_MESSAGE((jda.
c()) == (jdata.
c()), std::string(error_prefix +
" - Joint bias "));
86 (jda.
U()).isApprox(jdata.
U()),
87 std::string(error_prefix +
" - Joint U inertia matrix decomposition "));
90 std::string(error_prefix +
" - Joint DInv inertia matrix decomposition "));
93 std::string(error_prefix +
" - Joint UDInv inertia matrix decomposition "));
96 typedef typename JointModel::Constraint_t Constraint_t;
97 typedef typename Constraint_t::DenseBase ConstraintDense;
100 ConstraintDense vxS(
v.cross(jdata.
S()));
101 ConstraintDense vxS_ref =
v.toActionMatrix() * jdata.
S().matrix();
103 BOOST_CHECK_MESSAGE(vxS.isApprox(vxS_ref), std::string(error_prefix +
"- Joint vxS operation "));
107 const Inertia::Matrix6 Idense(Isparse.matrix());
109 const ConstraintDense IsparseS = Isparse * jdata.
S();
110 const ConstraintDense IdenseS = Idense * jdata.
S();
113 IdenseS.isApprox(IsparseS), std::string(error_prefix +
"- Joint YS operation "));
119 jmodel.
calc(jdata1.derived(),
q1, v1);
120 jmodel.
calc(jdata1.derived(),
Blank(), v2);
123 jmodel.
calc(jdata_ref.derived(),
q1, v2);
127 std::string(error_prefix +
"- joint.calc(jdata,*,v) "));
131 template<
typename Jo
intModel_>
134 template<
typename Jo
intModel_>
140 jmodel.setIndexes(0, 0, 0);
145 template<
typename Scalar,
int Options>
153 JointModel jmodel(Vector3::Random().normalized());
160 template<
typename Scalar,
int Options>
168 JointModel jmodel(Vector3::Random().normalized());
175 template<
typename Scalar,
int Options>
183 JointModel jmodel(Vector3::Random().normalized());
190 template<
typename Scalar,
int Options,
template<
typename,
int>
class JointCollection>
205 template<
typename Scalar,
int Options,
template<
typename,
int>
class JointCollection>
217 jmodel.setIndexes(0, 0, 0);
222 template<
typename Jo
intModel_>
238 template<
typename Scalar,
int Options>
253 template<
typename Scalar,
int Options,
int axis>
267 template<
typename Scalar,
int Options>
275 JointModel jmodel(Vector3::Random().normalized());
285 template<
typename Jo
intModel>
290 typename JointModel::JointDataDerived jdata = jmodel.
createData();
303 template<
typename Scalar,
int Options,
template<
typename,
int>
class JointCollectionTpl>
305 template<
typename Scalar,
int Options,
template<
typename,
int>
class JointCollectionTpl>
307 template<
typename Scalar,
int Options,
template<
typename,
int>
class JointCollectionTpl>
310 template<
typename _Scalar,
int _Options,
template<
typename,
int>
class JointCollectionTpl>
317 template<
typename _Scalar,
int _Options,
template<
typename,
int>
class JointCollectionTpl>
324 template<
typename _Scalar,
int _Options,
template<
typename,
int>
class JointCollectionTpl>
343 typedef Eigen::Matrix<Scalar, 6, Eigen::Dynamic, Options>
U_t;
344 typedef Eigen::Matrix<Scalar, Eigen::Dynamic, Eigen::Dynamic, Options>
D_t;
345 typedef Eigen::Matrix<Scalar, 6, Eigen::Dynamic, Options>
UD_t;
351 template<
typename _Scalar,
int _Options,
template<
typename,
int>
class JointCollectionTpl>
354 ,
JointModelBase<JointModelTest<_Scalar, _Options, JointCollectionTpl>>
371 BOOST_AUTO_TEST_SUITE(BOOST_TEST_MODULE)
383 std::vector<JointModelTest<double, 0, JointCollectionDefaultTpl>> jmodel_test_vector;
384 jmodel_test_vector.push_back(
387 std::vector<JointModelVariant> jmodel_variant_vector;
388 jmodel_variant_vector.push_back(jmodel_revolute_x);
390 std::vector<JointModel> jmodel_generic_vector;
391 jmodel_generic_vector.push_back((
JointModel)jmodel_revolute_x);
397 boost::mpl::for_each<JointModelVariant::types>(
TestJoint());
403 std::cout <<
"nq " << jmodel.nq() << std::endl;
404 std::cout <<
"nv " << jmodel.nv() << std::endl;
405 std::cout <<
"idx_q " << jmodel.idx_q() << std::endl;
406 std::cout <<
"idx_v " << jmodel.idx_v() << std::endl;
407 std::cout <<
"id " << jmodel.id() << std::endl;
408 std::cout <<
"name " << jmodel.
shortname() << std::endl;
410 BOOST_CHECK(jmodel.idx_q() == -1);
411 BOOST_CHECK(jmodel.idx_v() == -1);
419 BOOST_CHECK(joint_revolutex != joint_revolutey);
425 BOOST_CHECK(jmodelx_copy == jmodelx);
426 BOOST_CHECK(jmodelx_copy == jmodelx.derived());
431 BOOST_CHECK(jmodely != jmodelx);
441 BOOST_CHECK(jmodelx.
cast<
double>() == jmodelx);
442 BOOST_CHECK(jmodelx.
cast<
long double>().cast<
double>() == jmodelx);
448 template<
typename Jo
intModel>
452 typedef typename JointModel::JointDataDerived
JointData;
456 model.lowerPositionLimit.fill(-1.);
457 model.upperPositionLimit.fill(1.);
462 Eigen::VectorXd
v = Eigen::VectorXd::Random(
model.nv);
468 Eigen::VectorXd armature =
469 Eigen::VectorXd::Random(jmodel.nv()) + Eigen::VectorXd::Ones(jmodel.nv());
470 Inertia::Matrix6 I = Inertia::Matrix6::Identity();
471 jmodel.
calc_aba(jdata, armature, I,
false);
475 template<
typename Jo
intModel>
480 template<
typename Jo
intData>
485 std::cout <<
"name: " << jdata_generic1.
shortname() << std::endl;
486 BOOST_CHECK(jdata_generic1 == jdata_generic1);
495 BOOST_AUTO_TEST_SUITE_END()