13 #include <boost/test/unit_test.hpp>
29 model.appendBodyToJoint(idx,
Y);
32 BOOST_AUTO_TEST_SUITE(JointHelical)
39 Model modelHX, modelPXRX;
43 Inertia inertia_zero_mass(0.,
Vector3(0.0, 0.0, 0.0), Matrix3::Identity());
55 Data dataPXRX(modelPXRX);
58 Eigen::VectorXd q_hx = Eigen::VectorXd::Ones(modelHX.
nq);
59 Eigen::VectorXd q_PXRX = Eigen::VectorXd::Ones(modelPXRX.
nq);
60 q_PXRX(0) = q_hx(0) *
h;
62 Eigen::VectorXd v_hx = Eigen::VectorXd::Ones(modelHX.
nv);
63 Eigen::VectorXd v_PXRX = Eigen::VectorXd::Ones(modelPXRX.
nv);
64 v_PXRX(0) = v_hx(0) *
h;
66 Eigen::VectorXd tauHX = Eigen::VectorXd::Ones(modelHX.
nv);
67 Eigen::VectorXd tauPXRX = Eigen::VectorXd::Ones(modelPXRX.
nv);
68 Eigen::VectorXd aHX = Eigen::VectorXd::Ones(modelHX.
nv);
69 Eigen::VectorXd aPXRX = Eigen::VectorXd::Ones(modelPXRX.
nv);
70 aPXRX(0) = aHX(0) *
h *
h;
78 BOOST_CHECK(dataPXRX.oMi[2].isApprox(dataHX.oMi[1]));
79 BOOST_CHECK((dataPXRX.liMi[2] * dataPXRX.liMi[1]).isApprox(dataHX.liMi[1]));
80 BOOST_CHECK(dataPXRX.Ycrb[2].matrix().isApprox(dataHX.Ycrb[1].matrix()));
81 BOOST_CHECK((dataPXRX.liMi[2].actInv(dataPXRX.f[1])).toVector().isApprox(dataHX.f[1].toVector()));
83 (Eigen::Matrix<double, 1, 1>(dataPXRX.
nle.dot(Eigen::VectorXd::Ones(2)))).isApprox(dataHX.
nle));
84 BOOST_CHECK(dataPXRX.com[0].isApprox(dataHX.com[0]));
87 tauHX =
rnea(modelHX, dataHX, q_hx, v_hx, aHX);
88 tauPXRX =
rnea(modelPXRX, dataPXRX, q_PXRX, v_PXRX, aPXRX);
89 BOOST_CHECK(tauHX.isApprox(Eigen::Matrix<double, 1, 1>(tauPXRX.dot(Eigen::VectorXd::Ones(2)))));
95 BOOST_CHECK(aAbaHX.isApprox(aHX));
96 BOOST_CHECK(aAbaPXRX.isApprox(aPXRX));
97 BOOST_CHECK(aAbaPXRX.isApprox(Eigen::Matrix<double, 2, 1>(aHX(0) *
h *
h, aHX(0))));
102 BOOST_CHECK(aAbaHX.isApprox(aHX));
103 BOOST_CHECK(aAbaPXRX.isApprox(aPXRX));
104 BOOST_CHECK(aAbaPXRX.isApprox(Eigen::Matrix<double, 2, 1>(aHX(0) *
h *
h, aHX(0))));
110 tauHX = dataHX.
M * aHX;
111 tauPXRX = dataPXRX.
M * aPXRX;
113 BOOST_CHECK(tauHX.isApprox(Eigen::Matrix<double, 1, 1>(tauPXRX.dot(Eigen::VectorXd::Ones(2)))));
118 tauHX = dataHX.
M * aHX;
119 tauPXRX = dataPXRX.
M * aPXRX;
121 BOOST_CHECK(tauHX.isApprox(Eigen::Matrix<double, 1, 1>(tauPXRX.dot(Eigen::VectorXd::Ones(2)))));
126 Eigen::VectorXd v_body_hx = dataHX.
J * v_hx;
127 Eigen::VectorXd v_body_PXRX = dataPXRX.
J * v_PXRX;
128 BOOST_CHECK(v_body_hx.isApprox(v_body_PXRX));
139 const double alpha = 0.2,
h = 0.1;
140 double sin_alpha, cos_alpha;
144 TransformX Mx(sin_alpha, cos_alpha,
alpha *
h);
148 Mplain.
rotation().isApprox(Eigen::AngleAxisd(
alpha, Vector3::UnitX()).toRotationMatrix()));
149 BOOST_CHECK((Mrand * Mplain).
isApprox(Mrand * Mx));
151 TransformY My(sin_alpha, cos_alpha,
alpha *
h);
153 BOOST_CHECK(Mplain.translation().isApprox(Vector3::UnitY() *
alpha *
h));
155 Mplain.rotation().isApprox(Eigen::AngleAxisd(
alpha, Vector3::UnitY()).toRotationMatrix()));
156 BOOST_CHECK((Mrand * Mplain).
isApprox(Mrand * My));
158 TransformZ Mz(sin_alpha, cos_alpha,
alpha *
h);
160 BOOST_CHECK(Mplain.translation().isApprox(Vector3::UnitZ() *
alpha *
h));
162 Mplain.rotation().isApprox(Eigen::AngleAxisd(
alpha, Vector3::UnitZ()).toRotationMatrix()));
163 BOOST_CHECK((Mrand * Mplain).
isApprox(Mrand * Mz));
171 BOOST_CHECK(
M.act(mh_x).isApprox(
M.act(mh_dense_x)));
172 BOOST_CHECK(
M.actInv(mh_x).isApprox(
M.actInv(mh_dense_x)));
174 BOOST_CHECK(
v.cross(mh_x).isApprox(
v.cross(mh_dense_x)));
179 BOOST_CHECK(
M.act(mh_y).isApprox(
M.act(mh_dense_y)));
180 BOOST_CHECK(
M.actInv(mh_y).isApprox(
M.actInv(mh_dense_y)));
182 BOOST_CHECK(
v.cross(mh_y).isApprox(
v.cross(mh_dense_y)));
187 BOOST_CHECK(
M.act(mh_z).isApprox(
M.act(mh_dense_z)));
188 BOOST_CHECK(
M.actInv(mh_z).isApprox(
M.actInv(mh_dense_z)));
190 BOOST_CHECK(
v.cross(mh_z).isApprox(
v.cross(mh_dense_z)));
192 BOOST_AUTO_TEST_SUITE_END()
194 BOOST_AUTO_TEST_SUITE(JointHelicalUnaligned)
203 axis << 1.0, 0.0, 0.0;
204 const double h = 0.2;
206 Model modelHX, modelHelicalUnaligned;
210 pos.translation() = SE3::LinearType(1., 0., 0.);
215 addJointAndBody(modelHelicalUnaligned, joint_model_HU, 0,
pos,
"Helical-unaligned", inertia);
217 Data dataHX(modelHX);
218 Data dataHelicalUnaligned(modelHelicalUnaligned);
220 Eigen::VectorXd
q = 3 * Eigen::VectorXd::Ones(modelHX.
nq);
221 Eigen::VectorXd
v = 30 * Eigen::VectorXd::Ones(modelHX.
nv);
222 Eigen::VectorXd tauHX = Eigen::VectorXd::Ones(modelHX.
nv);
223 Eigen::VectorXd tauHelicalUnaligned = Eigen::VectorXd::Ones(modelHelicalUnaligned.
nv);
224 Eigen::VectorXd aHX = 5 * Eigen::VectorXd::Ones(modelHX.
nv);
225 Eigen::VectorXd aHelicalUnaligned(aHX);
233 BOOST_CHECK(dataHelicalUnaligned.oMi[1].isApprox(dataHX.oMi[1]));
234 BOOST_CHECK(dataHelicalUnaligned.liMi[1].isApprox(dataHX.liMi[1]));
235 BOOST_CHECK(dataHelicalUnaligned.Ycrb[1].matrix().isApprox(dataHX.Ycrb[1].matrix()));
236 BOOST_CHECK(dataHelicalUnaligned.f[1].toVector().isApprox(dataHX.f[1].toVector()));
238 BOOST_CHECK(dataHelicalUnaligned.
nle.isApprox(dataHX.
nle));
239 BOOST_CHECK(dataHelicalUnaligned.com[0].isApprox(dataHX.com[0]));
242 tauHX =
rnea(modelHX, dataHX,
q,
v, aHX);
243 tauHelicalUnaligned =
rnea(modelHelicalUnaligned, dataHelicalUnaligned,
q,
v, aHelicalUnaligned);
245 BOOST_CHECK(tauHX.isApprox(tauHelicalUnaligned));
249 Eigen::VectorXd aAbaHelicalUnaligned =
252 BOOST_CHECK(aAbaHX.isApprox(aAbaHelicalUnaligned));
258 BOOST_CHECK(dataHX.
M.isApprox(dataHelicalUnaligned.
M));
261 Eigen::Matrix<double, 6, Eigen::Dynamic> jacobianPX;
262 jacobianPX.resize(6, 1);
263 jacobianPX.setZero();
264 Eigen::Matrix<double, 6, Eigen::Dynamic> jacobianPrismaticUnaligned;
265 jacobianPrismaticUnaligned.resize(6, 1);
266 jacobianPrismaticUnaligned.setZero();
271 modelHelicalUnaligned, dataHelicalUnaligned, 1,
LOCAL, jacobianPrismaticUnaligned);
273 BOOST_CHECK(jacobianPX.isApprox(jacobianPrismaticUnaligned));
276 BOOST_AUTO_TEST_SUITE_END()