14 #include <boost/test/unit_test.hpp>
31 model.appendBodyToJoint(idx,
Y);
34 BOOST_AUTO_TEST_SUITE(JointRevoluteUnaligned)
43 axis << 1.0, 0.0, 0.0;
45 Model modelRX, modelRevoluteUnaligned;
49 pos.translation() = SE3::LinearType(1., 0., 0.);
54 addJointAndBody(modelRevoluteUnaligned, joint_model_RU, 0,
pos,
"revolute-unaligned", inertia);
57 Data dataRevoluteUnaligned(modelRevoluteUnaligned);
59 Eigen::VectorXd
q = Eigen::VectorXd::Ones(modelRX.
nq);
60 Eigen::VectorXd
v = Eigen::VectorXd::Ones(modelRX.
nv);
61 Eigen::VectorXd tauRX = Eigen::VectorXd::Ones(modelRX.
nv);
62 Eigen::VectorXd tauRevoluteUnaligned = Eigen::VectorXd::Ones(modelRevoluteUnaligned.
nv);
63 Eigen::VectorXd aRX = Eigen::VectorXd::Ones(modelRX.
nv);
64 Eigen::VectorXd aRevoluteUnaligned(aRX);
72 BOOST_CHECK(dataRevoluteUnaligned.oMi[1].isApprox(dataRX.oMi[1]));
73 BOOST_CHECK(dataRevoluteUnaligned.liMi[1].isApprox(dataRX.liMi[1]));
74 BOOST_CHECK(dataRevoluteUnaligned.Ycrb[1].matrix().isApprox(dataRX.Ycrb[1].matrix()));
75 BOOST_CHECK(dataRevoluteUnaligned.f[1].toVector().isApprox(dataRX.f[1].toVector()));
77 BOOST_CHECK(dataRevoluteUnaligned.
nle.isApprox(dataRX.
nle));
78 BOOST_CHECK(dataRevoluteUnaligned.com[0].isApprox(dataRX.com[0]));
81 tauRX =
rnea(modelRX, dataRX,
q,
v, aRX);
82 tauRevoluteUnaligned =
83 rnea(modelRevoluteUnaligned, dataRevoluteUnaligned,
q,
v, aRevoluteUnaligned);
85 BOOST_CHECK(tauRX.isApprox(tauRevoluteUnaligned));
89 Eigen::VectorXd aAbaRevoluteUnaligned =
aba(
90 modelRevoluteUnaligned, dataRevoluteUnaligned,
q,
v, tauRevoluteUnaligned,
Convention::WORLD);
92 BOOST_CHECK(aAbaRX.isApprox(aAbaRevoluteUnaligned));
98 BOOST_CHECK(dataRX.
M.isApprox(dataRevoluteUnaligned.
M));
101 Eigen::Matrix<double, 6, Eigen::Dynamic> jacobianRX;
102 jacobianRX.resize(6, 1);
103 jacobianRX.setZero();
104 Eigen::Matrix<double, 6, Eigen::Dynamic> jacobianRevoluteUnaligned;
105 jacobianRevoluteUnaligned.resize(6, 1);
106 jacobianRevoluteUnaligned.setZero();
111 modelRevoluteUnaligned, dataRevoluteUnaligned, 1,
LOCAL, jacobianRevoluteUnaligned);
113 BOOST_CHECK(jacobianRX.isApprox(jacobianRevoluteUnaligned));
115 BOOST_AUTO_TEST_SUITE_END()
117 BOOST_AUTO_TEST_SUITE(JointRevoluteUnboundedUnaligned)
126 axis << 1.0, 0.0, 0.0;
128 Model modelRUX, modelRevoluteUboundedUnaligned;
132 pos.translation() = SE3::LinearType(1., 0., 0.);
139 modelRevoluteUboundedUnaligned, joint_model_RUU, 0,
pos,
"revolute-unbounded-unaligned",
142 Data dataRUX(modelRUX);
143 Data dataRevoluteUnboundedUnaligned(modelRevoluteUboundedUnaligned);
145 Eigen::VectorXd
q = Eigen::VectorXd::Ones(modelRUX.
nq);
147 TangentVector
v = TangentVector::Ones(modelRUX.
nv);
148 Eigen::VectorXd tauRX = Eigen::VectorXd::Ones(modelRUX.
nv);
149 Eigen::VectorXd tauRevoluteUnaligned = Eigen::VectorXd::Ones(modelRevoluteUboundedUnaligned.
nv);
150 Eigen::VectorXd aRX = Eigen::VectorXd::Ones(modelRUX.
nv);
151 Eigen::VectorXd aRevoluteUnaligned(aRX);
157 computeAllTerms(modelRevoluteUboundedUnaligned, dataRevoluteUnboundedUnaligned,
q,
v);
159 BOOST_CHECK(dataRevoluteUnboundedUnaligned.oMi[1].isApprox(dataRUX.oMi[1]));
160 BOOST_CHECK(dataRevoluteUnboundedUnaligned.liMi[1].isApprox(dataRUX.liMi[1]));
161 BOOST_CHECK(dataRevoluteUnboundedUnaligned.Ycrb[1].matrix().isApprox(dataRUX.Ycrb[1].matrix()));
162 BOOST_CHECK(dataRevoluteUnboundedUnaligned.f[1].toVector().isApprox(dataRUX.f[1].toVector()));
164 BOOST_CHECK(dataRevoluteUnboundedUnaligned.
nle.isApprox(dataRUX.
nle));
165 BOOST_CHECK(dataRevoluteUnboundedUnaligned.com[0].isApprox(dataRUX.com[0]));
168 tauRX =
rnea(modelRUX, dataRUX,
q,
v, aRX);
169 tauRevoluteUnaligned =
170 rnea(modelRevoluteUboundedUnaligned, dataRevoluteUnboundedUnaligned,
q,
v, aRevoluteUnaligned);
172 BOOST_CHECK(tauRX.isApprox(tauRevoluteUnaligned));
176 Eigen::VectorXd aAbaRevoluteUnaligned =
aba(
177 modelRevoluteUboundedUnaligned, dataRevoluteUnboundedUnaligned,
q,
v, tauRevoluteUnaligned,
180 BOOST_CHECK(aAbaRX.isApprox(aAbaRevoluteUnaligned));
186 BOOST_CHECK(dataRUX.
M.isApprox(dataRevoluteUnboundedUnaligned.
M));
190 jacobianRUX.resize(6, 1);
191 jacobianRUX.setZero();
193 jacobianRevoluteUnboundedUnaligned.resize(6, 1);
194 jacobianRevoluteUnboundedUnaligned.setZero();
200 modelRevoluteUboundedUnaligned, dataRevoluteUnboundedUnaligned, 1,
LOCAL,
201 jacobianRevoluteUnboundedUnaligned);
203 BOOST_CHECK(jacobianRUX.isApprox(jacobianRevoluteUnboundedUnaligned));
206 BOOST_AUTO_TEST_SUITE_END()
208 BOOST_AUTO_TEST_SUITE(JointRevoluteUnbounded)
218 BOOST_CHECK(
M.act(mp_x).isApprox(
M.act(mp_dense_x)));
219 BOOST_CHECK(
M.actInv(mp_x).isApprox(
M.actInv(mp_dense_x)));
221 BOOST_CHECK(
v.cross(mp_x).isApprox(
v.cross(mp_dense_x)));
226 BOOST_CHECK(
M.act(mp_y).isApprox(
M.act(mp_dense_y)));
227 BOOST_CHECK(
M.actInv(mp_y).isApprox(
M.actInv(mp_dense_y)));
229 BOOST_CHECK(
v.cross(mp_y).isApprox(
v.cross(mp_dense_y)));
234 BOOST_CHECK(
M.act(mp_z).isApprox(
M.act(mp_dense_z)));
235 BOOST_CHECK(
M.actInv(mp_z).isApprox(
M.actInv(mp_dense_z)));
237 BOOST_CHECK(
v.cross(mp_z).isApprox(
v.cross(mp_dense_z)));
245 Model modelRX, modelRevoluteUnbounded;
249 pos.translation() = SE3::LinearType(1., 0., 0.);
254 modelRevoluteUnbounded, joint_model_RUX, 0,
SE3::Identity(),
"revolute unbounded x", inertia);
256 Data dataRX(modelRX);
257 Data dataRevoluteUnbounded(modelRevoluteUnbounded);
259 Eigen::VectorXd q_rx = Eigen::VectorXd::Ones(modelRX.
nq);
260 Eigen::VectorXd q_rubx = Eigen::VectorXd::Ones(modelRevoluteUnbounded.
nq);
262 double alpha = q_rx(0);
266 Eigen::VectorXd v_rx = Eigen::VectorXd::Ones(modelRX.
nv);
267 Eigen::VectorXd v_rubx = v_rx;
268 Eigen::VectorXd tauRX = Eigen::VectorXd::Ones(modelRX.
nv);
269 Eigen::VectorXd tauRevoluteUnbounded = Eigen::VectorXd::Ones(modelRevoluteUnbounded.
nv);
270 Eigen::VectorXd aRX = Eigen::VectorXd::Ones(modelRX.
nv);
271 Eigen::VectorXd aRevoluteUnbounded = aRX;
274 forwardKinematics(modelRevoluteUnbounded, dataRevoluteUnbounded, q_rubx, v_rubx);
277 computeAllTerms(modelRevoluteUnbounded, dataRevoluteUnbounded, q_rubx, v_rubx);
279 BOOST_CHECK(dataRevoluteUnbounded.oMi[1].isApprox(dataRX.oMi[1]));
280 BOOST_CHECK(dataRevoluteUnbounded.liMi[1].isApprox(dataRX.liMi[1]));
281 BOOST_CHECK(dataRevoluteUnbounded.Ycrb[1].matrix().isApprox(dataRX.Ycrb[1].matrix()));
282 BOOST_CHECK(dataRevoluteUnbounded.f[1].toVector().isApprox(dataRX.f[1].toVector()));
284 BOOST_CHECK(dataRevoluteUnbounded.nle.isApprox(dataRX.nle));
285 BOOST_CHECK(dataRevoluteUnbounded.com[0].isApprox(dataRX.com[0]));
288 tauRX =
rnea(modelRX, dataRX, q_rx, v_rx, aRX);
289 tauRevoluteUnbounded =
290 rnea(modelRevoluteUnbounded, dataRevoluteUnbounded, q_rubx, v_rubx, aRevoluteUnbounded);
292 BOOST_CHECK(tauRX.isApprox(tauRevoluteUnbounded));
296 Eigen::VectorXd aAbaRevoluteUnbounded =
aba(
297 modelRevoluteUnbounded, dataRevoluteUnbounded, q_rubx, v_rubx, tauRevoluteUnbounded,
300 BOOST_CHECK(aAbaRX.isApprox(aAbaRevoluteUnbounded));
306 BOOST_CHECK(dataRX.M.isApprox(dataRevoluteUnbounded.M));
309 Eigen::Matrix<double, 6, Eigen::Dynamic> jacobianPX;
310 jacobianPX.resize(6, 1);
311 jacobianPX.setZero();
312 Eigen::Matrix<double, 6, Eigen::Dynamic> jacobianPrismaticUnaligned;
313 jacobianPrismaticUnaligned.resize(6, 1);
314 jacobianPrismaticUnaligned.setZero();
319 modelRevoluteUnbounded, dataRevoluteUnbounded, 1,
LOCAL, jacobianPrismaticUnaligned);
321 BOOST_CHECK(jacobianPX.isApprox(jacobianPrismaticUnaligned));
323 BOOST_AUTO_TEST_SUITE_END()
325 BOOST_AUTO_TEST_SUITE(JointRevolute)
335 const double alpha = 0.2;
336 double sin_alpha, cos_alpha;
340 TransformX Mx(sin_alpha, cos_alpha);
344 Mplain.
rotation().isApprox(Eigen::AngleAxisd(
alpha, Vector3::UnitX()).toRotationMatrix()));
345 BOOST_CHECK((Mrand * Mplain).
isApprox(Mrand * Mx));
347 TransformY My(sin_alpha, cos_alpha);
349 BOOST_CHECK(Mplain.translation().isZero());
351 Mplain.rotation().isApprox(Eigen::AngleAxisd(
alpha, Vector3::UnitY()).toRotationMatrix()));
352 BOOST_CHECK((Mrand * Mplain).
isApprox(Mrand * My));
354 TransformZ Mz(sin_alpha, cos_alpha);
356 BOOST_CHECK(Mplain.translation().isZero());
358 Mplain.rotation().isApprox(Eigen::AngleAxisd(
alpha, Vector3::UnitZ()).toRotationMatrix()));
359 BOOST_CHECK((Mrand * Mplain).
isApprox(Mrand * Mz));
367 BOOST_CHECK(
M.act(mp_x).isApprox(
M.act(mp_dense_x)));
368 BOOST_CHECK(
M.actInv(mp_x).isApprox(
M.actInv(mp_dense_x)));
370 BOOST_CHECK(
v.cross(mp_x).isApprox(
v.cross(mp_dense_x)));
375 BOOST_CHECK(
M.act(mp_y).isApprox(
M.act(mp_dense_y)));
376 BOOST_CHECK(
M.actInv(mp_y).isApprox(
M.actInv(mp_dense_y)));
378 BOOST_CHECK(
v.cross(mp_y).isApprox(
v.cross(mp_dense_y)));
383 BOOST_CHECK(
M.act(mp_z).isApprox(
M.act(mp_dense_z)));
384 BOOST_CHECK(
M.actInv(mp_z).isApprox(
M.actInv(mp_dense_z)));
386 BOOST_CHECK(
v.cross(mp_z).isApprox(
v.cross(mp_dense_z)));
389 BOOST_AUTO_TEST_SUITE_END()
391 BOOST_AUTO_TEST_SUITE(JointRevoluteUnaligned)
401 BOOST_CHECK(
M.act(mp).isApprox(
M.act(mp_dense)));
402 BOOST_CHECK(
M.actInv(mp).isApprox(
M.actInv(mp_dense)));
404 BOOST_CHECK(
v.cross(mp).isApprox(
v.cross(mp_dense)));
407 BOOST_AUTO_TEST_SUITE_END()