14 #include <boost/test/unit_test.hpp>
31 model.appendBodyToJoint(idx,
Y);
34 BOOST_AUTO_TEST_SUITE(JointSpherical)
44 BOOST_CHECK(
M.act(mp).isApprox(
M.act(mp_dense)));
45 BOOST_CHECK(
M.actInv(mp).isApprox(
M.actInv(mp_dense)));
47 BOOST_CHECK(
v.cross(mp).isApprox(
v.cross(mp_dense)));
54 typedef Eigen::Matrix<double, 6, 1> Vector6;
55 typedef Eigen::Matrix<double, 7, 1> VectorFF;
58 Model modelSpherical, modelFreeflyer;
62 pos.translation() = SE3::LinearType(1., 0., 0.);
67 Data dataSpherical(modelSpherical);
68 Data dataFreeFlyer(modelFreeflyer);
70 Eigen::VectorXd
q = Eigen::VectorXd::Ones(modelSpherical.
nq);
73 qff << 0, 0, 0,
q[0],
q[1],
q[2],
q[3];
74 Eigen::VectorXd
v = Eigen::VectorXd::Ones(modelSpherical.
nv);
76 vff << 0, 0, 0, 1, 1, 1;
77 Eigen::VectorXd tauSpherical = Eigen::VectorXd::Ones(modelSpherical.
nv);
78 Eigen::VectorXd tauff;
80 tauff << 0, 0, 0, 1, 1, 1, 1;
81 Eigen::VectorXd aSpherical = Eigen::VectorXd::Ones(modelSpherical.
nv);
82 Eigen::VectorXd aff(vff);
90 BOOST_CHECK(dataFreeFlyer.oMi[1].isApprox(dataSpherical.oMi[1]));
91 BOOST_CHECK(dataFreeFlyer.liMi[1].isApprox(dataSpherical.liMi[1]));
92 BOOST_CHECK(dataFreeFlyer.Ycrb[1].matrix().isApprox(dataSpherical.Ycrb[1].matrix()));
93 BOOST_CHECK(dataFreeFlyer.f[1].toVector().isApprox(dataSpherical.f[1].toVector()));
95 Eigen::VectorXd nle_expected_ff(3);
96 nle_expected_ff << dataFreeFlyer.
nle[3], dataFreeFlyer.
nle[4], dataFreeFlyer.
nle[5];
97 BOOST_CHECK(nle_expected_ff.isApprox(dataSpherical.
nle));
98 BOOST_CHECK(dataFreeFlyer.com[0].isApprox(dataSpherical.com[0]));
101 tauSpherical =
rnea(modelSpherical, dataSpherical,
q,
v, aSpherical);
102 tauff =
rnea(modelFreeflyer, dataFreeFlyer, qff, vff, aff);
105 tau_expected << tauff(3), tauff(4), tauff(5);
106 BOOST_CHECK(tauSpherical.isApprox(tau_expected));
109 Eigen::VectorXd aAbaSpherical =
111 Eigen::VectorXd aAbaFreeFlyer =
114 a_expected << aAbaFreeFlyer[3], aAbaFreeFlyer[4], aAbaFreeFlyer[5];
115 BOOST_CHECK(aAbaSpherical.isApprox(a_expected));
121 Eigen::Matrix<double, 3, 3> M_expected(dataFreeFlyer.
M.bottomRightCorner<3, 3>());
123 BOOST_CHECK(dataSpherical.
M.isApprox(M_expected));
126 Eigen::Matrix<double, 6, Eigen::Dynamic> jacobian_planar;
127 jacobian_planar.resize(6, 3);
128 jacobian_planar.setZero();
129 Eigen::Matrix<double, 6, Eigen::Dynamic> jacobian_ff;
130 jacobian_ff.resize(6, 6);
131 jacobian_ff.setZero();
137 Eigen::Matrix<double, 6, 3> jacobian_expected;
138 jacobian_expected << jacobian_ff.col(3), jacobian_ff.col(4), jacobian_ff.col(5);
140 BOOST_CHECK(jacobian_planar.isApprox(jacobian_expected));
142 BOOST_AUTO_TEST_SUITE_END()
144 BOOST_AUTO_TEST_SUITE(JointSphericalZYX)
154 BOOST_CHECK(
M.act(mp).isApprox(
M.act(mp_dense)));
155 BOOST_CHECK(
M.actInv(mp).isApprox(
M.actInv(mp_dense)));
157 BOOST_CHECK(
v.cross(mp).isApprox(
v.cross(mp_dense)));
166 typedef Eigen::Matrix<double, 6, 1> Vector6;
167 typedef Eigen::Matrix<double, 7, 1> VectorFF;
170 Model modelSphericalZYX, modelFreeflyer;
174 pos.translation() = SE3::LinearType(1., 0., 0.);
179 Data dataSphericalZYX(modelSphericalZYX);
180 Data dataFreeFlyer(modelFreeflyer);
182 Eigen::AngleAxisd rollAngle(1, Eigen::Vector3d::UnitZ());
183 Eigen::AngleAxisd yawAngle(1, Eigen::Vector3d::UnitY());
184 Eigen::AngleAxisd pitchAngle(1, Eigen::Vector3d::UnitX());
185 Eigen::Quaterniond q_sph = rollAngle * yawAngle * pitchAngle;
187 Eigen::VectorXd
q = Eigen::VectorXd::Ones(modelSphericalZYX.
nq);
189 qff << 0, 0, 0, q_sph.x(), q_sph.y(), q_sph.z(), q_sph.w();
190 Eigen::VectorXd
v = Eigen::VectorXd::Ones(modelSphericalZYX.
nv);
192 vff << 0, 0, 0, 1, 1, 1;
193 Eigen::VectorXd tauSpherical = Eigen::VectorXd::Ones(modelSphericalZYX.
nv);
194 Eigen::VectorXd tauff;
196 tauff << 0, 0, 0, 1, 1, 1;
197 Eigen::VectorXd aSpherical = Eigen::VectorXd::Ones(modelSphericalZYX.
nv);
198 Eigen::VectorXd aff(vff);
206 BOOST_CHECK(dataFreeFlyer.oMi[1].isApprox(dataSphericalZYX.oMi[1]));
207 BOOST_CHECK(dataFreeFlyer.liMi[1].isApprox(dataSphericalZYX.liMi[1]));
208 BOOST_CHECK(dataFreeFlyer.Ycrb[1].matrix().isApprox(dataSphericalZYX.Ycrb[1].matrix()));
210 BOOST_CHECK(dataFreeFlyer.com[0].isApprox(dataSphericalZYX.com[0]));
228 Eigen::VectorXd
q = Eigen::VectorXd::Zero(
model.nq);
229 Eigen::VectorXd
v = Eigen::VectorXd::Zero(
model.nv);
230 Eigen::VectorXd
a = Eigen::VectorXd::Zero(
model.nv);
233 Vector3 tau_expected(0., -4.905, 0.);
235 BOOST_CHECK(tau_expected.isApprox(
data.tau, 1e-14));
237 q = Eigen::VectorXd::Ones(
model.nq);
238 v = Eigen::VectorXd::Ones(
model.nv);
239 a = Eigen::VectorXd::Ones(
model.nv);
242 tau_expected << -0.53611600195085, -0.74621832606188, -0.38177329067604;
244 BOOST_CHECK(tau_expected.isApprox(
data.tau, 1e-12));
247 v = Eigen::VectorXd::Ones(
model.nv);
248 a = Eigen::VectorXd::Ones(
model.nv);
251 tau_expected << 0.73934458094049, 2.7804530848031, 0.50684940972146;
253 BOOST_CHECK(tau_expected.isApprox(
data.tau, 1e-12));
272 Eigen::VectorXd
q(Eigen::VectorXd::Zero(
model.nq));
273 Eigen::MatrixXd M_expected(
model.nv,
model.nv);
276 M_expected << 1.25, 0, 0, 0, 1.25, 0, 0, 0, 1;
278 BOOST_CHECK(M_expected.isApprox(
data.M, 1e-14));
280 q = Eigen::VectorXd::Ones(
model.nq);
283 M_expected << 1.0729816454316, -5.5511151231258e-17, -0.8414709848079, -5.5511151231258e-17, 1.25,
284 0, -0.8414709848079, 0, 1;
286 BOOST_CHECK(M_expected.isApprox(
data.M, 1e-12));
291 M_expected << 1.043294547392, 2.7755575615629e-17, -0.90929742682568, 0, 1.25, 0,
292 -0.90929742682568, 0, 1;
294 BOOST_CHECK(M_expected.isApprox(
data.M, 1e-10));
297 BOOST_AUTO_TEST_SUITE_END()