19 #include <boost/test/unit_test.hpp>
20 #include <boost/utility/binary.hpp>
22 template<
typename Derived>
23 inline bool isFinite(
const Eigen::MatrixBase<Derived> & x)
25 return ((
x -
x).array() == (
x -
x).array()).all();
28 BOOST_AUTO_TEST_SUITE(BOOST_TEST_MODULE)
36 BOOST_CHECK(
model.frames.size() >=
size_t(
model.njoints));
37 for (Model::FrameVector::const_iterator
it =
model.frames.begin();
it !=
model.frames.end(); ++
it)
42 BOOST_CHECK(frame_copy ==
frame);
46 std::ostringstream os;
47 os << frame1 << std::endl;
48 BOOST_CHECK(!os.str().empty());
52 BOOST_CHECK(frame1 == frame2);
61 BOOST_CHECK(
frame.cast<
double>().cast<
long double>() ==
frame.cast<
long double>());
64 Frameld frame2(
frame);
66 BOOST_CHECK(frame2 ==
frame.cast<
long double>());
71 using namespace Eigen;
78 const std::string & frame_name = std::string(
model.names[parent_idx] +
"_frame");
79 const SE3 & framePlacement = SE3::Random();
83 VectorXd
q = VectorXd::Ones(
model.nq);
88 data.oMf[
model.getFrameId(frame_name)].isApprox(
data.oMi[parent_idx] * framePlacement));
93 using namespace Eigen;
100 const std::string & frame_name = std::string(
model.names[parent_idx] +
"_frame");
101 const SE3 & framePlacement = SE3::Random();
107 VectorXd
q = VectorXd::Ones(
model.nq);
115 BOOST_CHECK(
data.oMf[frame_idx].isApprox(data_ref.oMf[frame_idx]));
120 using namespace Eigen;
127 const std::string & frame_name = std::string(
model.names[parent_idx] +
"_frame");
128 const SE3 & framePlacement = SE3::Random();
134 VectorXd
q = VectorXd::Ones(
model.nq);
142 BOOST_CHECK(
data.oMf[frame_idx].isApprox(data_ref.oMf[frame_idx]));
147 using namespace Eigen;
154 const std::string & frame_name = std::string(
model.names[parent_idx] +
"_frame");
155 const SE3 & framePlacement = SE3::Random();
160 VectorXd
q = VectorXd::Ones(
model.nq);
162 VectorXd
v = VectorXd::Ones(
model.nv);
167 BOOST_CHECK(vf.isApprox(framePlacement.actInv(
data.v[parent_idx])));
178 BOOST_CHECK(
SE3(data_ref.oMf[frame_idx].rotation(), Eigen::Vector3d::Zero())
185 using namespace Eigen;
192 const std::string & frame_name = std::string(
model.names[parent_idx] +
"_frame");
193 const SE3 & framePlacement = SE3::Random();
198 VectorXd
q = VectorXd::Ones(
model.nq);
200 VectorXd
v = VectorXd::Ones(
model.nv);
201 VectorXd
a = VectorXd::Ones(
model.nv);
206 BOOST_CHECK(af.isApprox(framePlacement.actInv(
data.a[parent_idx])));
215 BOOST_CHECK(data_ref.oMf[frame_idx].act(a_ref).isApprox(
217 BOOST_CHECK(
SE3(data_ref.oMf[frame_idx].rotation(), Eigen::Vector3d::Zero())
224 using namespace Eigen;
231 const std::string & frame_name = std::string(
model.names[parent_idx] +
"_frame");
232 const SE3 & framePlacement = SE3::Random();
237 VectorXd
q = VectorXd::Ones(
model.nq);
239 VectorXd
v = VectorXd::Ones(
model.nv);
240 VectorXd
a = VectorXd::Ones(
model.nv);
243 Motion vel = framePlacement.actInv(
data.v[parent_idx]);
248 linear =
acc.linear() + vel.angular().cross(vel.linear());
249 acc_classical_local.linear() = linear;
253 BOOST_CHECK(af.isApprox(acc_classical_local));
259 SE3 T_ref = data_ref.oMf[frame_idx];
263 Motion acc_classical_local_ref = a_ref;
264 linear = a_ref.linear() +
v_ref.angular().cross(
v_ref.linear());
265 acc_classical_local_ref.linear() = linear;
273 Motion acc_classical_world_ref = T_ref.act(a_ref);
274 linear = acc_classical_world_ref.linear() + vel_world_ref.angular().cross(vel_world_ref.linear());
275 acc_classical_world_ref.linear() = linear;
281 Motion acc_classical_aligned_ref =
SE3(T_ref.
rotation(), Eigen::Vector3d::Zero()).act(a_ref);
283 acc_classical_aligned_ref.linear() + vel_aligned_ref.angular().cross(vel_aligned_ref.linear());
284 acc_classical_aligned_ref.linear() = linear;
286 BOOST_CHECK(acc_classical_aligned_ref.isApprox(
292 using namespace Eigen;
299 Frame(
"Frame1", parentId, 0,
SE3(Matrix3d::Identity(), Vector3d(1.0, 0.0, 0.0)),
OP_FRAME));
315 v_local.linear() = Vector3d(0.0, 1.0, 0.0);
316 v_local.angular() = Vector3d(0.0, 0.0, 1.0);
319 v_world.linear() = Vector3d::Zero();
320 v_world.angular() = Vector3d(0.0, 0.0, 1.0);
323 v_align.linear() = Vector3d(-1.0, 0.0, 0.0);
324 v_align.angular() = Vector3d(0.0, 0.0, 1.0);
328 ac_local.linear() = Vector3d(-1.0, 0.0, 0.0);
329 ac_local.angular() = Vector3d::Zero();
331 Motion ac_world = Motion::Zero();
334 ac_align.linear() = Vector3d(0.0, -1.0, 0.0);
335 ac_align.angular() = Vector3d::Zero();
362 using namespace Eigen;
369 const std::string & frame_name = std::string(
model.names[parent_idx] +
"_frame");
370 const SE3 & framePlacement = SE3::Random();
372 BOOST_CHECK(
model.existFrame(frame_name));
377 model.lowerPositionLimit.head<7>().
fill(-1.);
378 model.upperPositionLimit.head<7>().
fill(1.);
380 VectorXd
v = VectorXd::Ones(
model.nv);
385 BOOST_CHECK(
frame.placement.isApprox_impl(framePlacement));
403 const SE3::ActionMatrixType jXf =
frame.placement.toActionMatrix();
405 BOOST_CHECK(Jjj_from_frame.isApprox(Jjj));
407 BOOST_CHECK(nu_frame.isApprox(
frame.placement.actInv(nu_joint)));
416 BOOST_CHECK(Jff.isApprox(Jjj));
420 BOOST_CHECK(Jff2.isApprox(Jjj));
430 const SE3 oMf_translation(SE3::Matrix3::Identity(),
data.oMf[idx].translation());
431 Jjj = oMf_translation.toActionMatrixInverse() * Jjj;
432 BOOST_CHECK(Jff.isApprox(Jjj));
435 BOOST_CHECK(Jff2.isApprox(Jff));
440 using namespace Eigen;
447 const std::string & frame_name = std::string(
model.names[parent_idx] +
"_frame");
448 const SE3 & framePlacement = SE3::Random();
450 BOOST_CHECK(
model.existFrame(frame_name));
455 model.lowerPositionLimit.head<7>().
fill(-1.);
456 model.upperPositionLimit.head<7>().
fill(1.);
458 VectorXd
v = VectorXd::Ones(
model.nv);
462 BOOST_CHECK(
frame.placement.isApprox_impl(framePlacement));
476 BOOST_CHECK(Jf.isApprox(Jf_ref));
480 BOOST_CHECK(Jf2.isApprox(Jf_ref));
485 using namespace Eigen;
492 const std::string & frame_name = std::string(
model.names[parent_idx] +
"_frame");
493 const SE3 & framePlacement = SE3::Random();
495 BOOST_CHECK(
model.existFrame(frame_name));
499 model.lowerPositionLimit.head<7>().
fill(-1.);
500 model.upperPositionLimit.head<7>().
fill(1.);
502 VectorXd
v = VectorXd::Ones(
model.nv);
517 Jf_ref =
SE3(
data.oMf[idx].rotation(), Eigen::Vector3d::Zero()).toActionMatrix() * Jf_ref;
520 BOOST_CHECK(Jf.isApprox(Jf_ref));
524 BOOST_CHECK(Jf2.isApprox(Jf_ref));
529 using namespace Eigen;
536 const std::string & frame_name = std::string(
model.names[parent_idx] +
"_frame");
537 const SE3 & framePlacement = SE3::Random();
543 model, -1 * Eigen::VectorXd::Ones(
model.nq), Eigen::VectorXd::Ones(
model.nq));
544 VectorXd
v = VectorXd::Random(
model.nv);
545 VectorXd
a = VectorXd::Random(
model.nv);
557 BOOST_CHECK(
frame.placement.isApprox_impl(framePlacement));
569 const Motion & v_ref_local =
frame.placement.actInv(data_ref.v[parent_idx]);
570 const Motion &
v_ref = data_ref.oMf[idx].act(v_ref_local);
572 const SE3 wMf =
SE3(data_ref.oMf[idx].rotation(), SE3::Vector3::Zero());
573 const Motion v_ref_local_world_aligned = wMf.act(v_ref_local);
574 BOOST_CHECK(v_idx.isApprox(
v_ref));
577 const Motion a_ref_local =
frame.placement.actInv(data_ref.a[parent_idx]);
578 const Motion a_ref = data_ref.oMf[idx].act(a_ref_local);
579 const Motion a_ref_local_world_aligned = wMf.act(a_ref_local);
580 BOOST_CHECK(a_idx.isApprox(a_ref));
588 v_idx = (Motion::Vector6)(
J *
v);
589 BOOST_CHECK(v_idx.isApprox(v_ref_local));
591 a_idx = (Motion::Vector6)(
J *
a + dJ *
v);
592 BOOST_CHECK(a_idx.isApprox(a_ref_local));
598 world_v_frame.linear().setZero();
600 v_idx = (Motion::Vector6)(
J *
v);
601 BOOST_CHECK(v_idx.isApprox(v_ref_local_world_aligned));
603 a_idx = (Motion::Vector6)(
J *
a + dJ *
v);
605 a_idx.isApprox(world_v_frame.cross(wMf.act(v_ref_local)) + a_ref_local_world_aligned));
611 const double alpha = 1e-8;
612 Eigen::VectorXd q_plus(
model.nq);
617 J_ref_local_world_aligned(6,
model.nv);
618 J_ref_world.fill(0.);
619 J_ref_local.fill(0.);
620 J_ref_local_world_aligned.fill(0.);
629 J_ref_plus_local_world_aligned(6,
model.nv);
630 J_ref_plus_world.fill(0.);
631 J_ref_plus_local.fill(0.);
632 J_ref_plus_local_world_aligned.fill(0.);
641 dJ_ref_local_world_aligned(6,
model.nv);
642 dJ_ref_world.fill(0.);
643 dJ_ref_local.fill(0.);
644 dJ_ref_local_world_aligned.fill(0.);
645 dJ_ref_world = (J_ref_plus_world - J_ref_world) /
alpha;
646 dJ_ref_local = (J_ref_plus_local - J_ref_local) /
alpha;
647 dJ_ref_local_world_aligned =
648 (J_ref_plus_local_world_aligned - J_ref_local_world_aligned) /
alpha;
655 dJ_local_world_aligned(6,
model.nv);
658 dJ_local_world_aligned.fill(0.);
663 BOOST_CHECK(dJ_world.isApprox(dJ_ref_world, sqrt(
alpha)));
664 BOOST_CHECK(dJ_local.isApprox(dJ_ref_local, sqrt(
alpha)));
665 BOOST_CHECK(dJ_local_world_aligned.isApprox(dJ_ref_local_world_aligned, sqrt(
alpha)));
671 using namespace Eigen;
677 Data data_free(model_free);
684 const std::string
joint_name =
"chest2_joint";
689 Data data_fix(model_fix);
698 VectorXd v_free(VectorXd::Random(model_free.
nv));
699 VectorXd a_free(VectorXd::Random(model_free.
nv));
702 q_free[joint_idx_q] = 0;
703 v_free[joint_idx_v] = 0;
704 a_free[joint_idx_v] = 0;
707 VectorXd q_fix(model_fix.
nq);
708 q_fix << q_free.head(joint_idx_q), q_free.tail(model_free.
nq - joint_idx_q - 1);
709 VectorXd v_fix(model_fix.
nv);
710 v_fix << v_free.head(joint_idx_v), v_free.tail(model_free.
nv - joint_idx_v - 1);
711 VectorXd a_fix(model_fix.
nv);
712 a_fix << a_free.head(joint_idx_v), a_free.tail(model_free.
nv - joint_idx_v - 1);
720 BOOST_CHECK(inertia_fix.isApprox(inertia_free));
724 BOOST_CHECK(inertia_fix.isApprox(inertia_free));
726 rnea(model_fix, data_fix, q_fix, v_fix, a_fix);
727 rnea(model_free, data_free, q_free, v_free, a_free);
731 BOOST_CHECK(force_fix.isApprox(force_free));
733 BOOST_AUTO_TEST_SUITE_END()