18 #include <boost/test/unit_test.hpp>
19 #include <boost/filesystem/fstream.hpp>
24 struct TemporaryFileHolder
27 :
path(
boost::filesystem::temp_directory_path() /
boost::filesystem::unique_path())
31 ~TemporaryFileHolder()
33 boost::filesystem::remove(
path);
36 TemporaryFileHolder(
const TemporaryFileHolder &) =
delete;
37 TemporaryFileHolder &
operator=(
const TemporaryFileHolder &) =
delete;
39 TemporaryFileHolder(TemporaryFileHolder &&) =
default;
40 TemporaryFileHolder &
operator=(TemporaryFileHolder &&) =
default;
42 std::string
name()
const
54 TemporaryFileHolder temp_file;
57 boost::filesystem::ofstream file_stream(temp_file.path);
60 std::cerr <<
"Error opening file for writing" << std::endl;
63 file_stream <<
data.rdbuf();
73 if (pt1.size() != pt2.size())
77 for (
auto it1 = pt1.begin(), it2 = pt2.begin(); it1 != pt1.end(); ++it1, ++it2)
80 if (it1->first != it2->first)
84 if (it1->second.data() != it2->second.data())
95 BOOST_AUTO_TEST_SUITE(BOOST_TEST_MODULE)
104 std::istringstream xmlData(R
"(
105 <inertial mass="0.629769" pos="-0.041018 -0.00014 0.049974"
106 fullinertia="0.00315 0.00388 0.004285 8.2904e-7 0.00015 8.2299e-6"/>
111 boost::property_tree::read_xml(xmlData, pt);
113 typedef ::pinocchio::mjcf::details::MjcfGraph MjcfGraph;
117 MjcfGraph
graph(visitor,
"fakeMjcf");
122 Matrix3 inertia_matrix;
124 inertia_matrix << 0.00315, 8.2904e-7, 0.00015, 8.2904e-7, 0.00388, 8.2299e-6, 0.00015, 8.2299e-6,
128 BOOST_CHECK(inertia.
isEqual(real_inertia));
138 std::istringstream xmlData(R
"(
139 <inertial mass="0.629769" pos="-0.041018 -0.00014 0.049974"
140 diaginertia="0.00315 0.00388 0.004285"/>
145 boost::property_tree::read_xml(xmlData, pt);
147 typedef ::pinocchio::mjcf::details::MjcfGraph MjcfGraph;
151 MjcfGraph
graph(visitor,
"fakeMjcf");
156 Matrix3 inertia_matrix = Eigen::Matrix3d::Zero();
157 inertia_matrix(0, 0) = 0.00315;
158 inertia_matrix(1, 1) = 0.00388;
159 inertia_matrix(2, 2) = 0.004285;
162 BOOST_CHECK(inertia.isApprox(real_inertia, 1e-7));
168 double pi = boost::math::constants::pi<double>();
170 std::istringstream xmlData(R
"(<mujoco model="inertiaFromGeom">
171 <compiler inertiafromgeom="true" />
173 <body pos="0 0 0" name="bodyCylinder">
174 <geom type="cylinder" size=".01" fromto="0 0 0 0 0 .5"/>
175 <geom type="cylinder" size=".01 0.25" pos="0 0 0" quat="1 0 0 0"/>
176 <body pos="0 0 0" name="bodyBox">
177 <geom type="box" size=".01" fromto="0 0 0 0 0 .5"/>
178 <geom type="box" size=".01 0.01 0.25" pos="0 0 0" quat="1 0 0 0"/>
180 <body pos="0 0 0" name="bodyCapsule">
181 <geom type="capsule" size=".01" fromto="0 0 0 0 0 .5"/>
182 <geom type="capsule" size=".01 0.25" pos="0 0 0" quat="1 0 0 0"/>
184 <body pos="0 0 0" name="bodySphere">
185 <geom type="sphere" size=".01 0.25" pos="0 0 0" quat="1 0 0 0"/>
187 <body pos="0 0 0" name="bodyEllip">
188 <geom type="ellipsoid" size=".01" fromto="0 0 0 0 0 .5"/>
189 <geom type="ellipsoid" size=".01 0.01 0.25" pos="0 0 0" quat="1 0 0 0"/>
197 typedef ::pinocchio::mjcf::details::MjcfGraph MjcfGraph;
201 MjcfGraph
graph(visitor,
"fakeMjcf");
202 graph.parseGraphFromXML(namefile.name());
206 double mass = 1000 * std::pow(0.01, 2) * 0.25 * pi * 2;
208 Eigen::Vector2d sizeCy;
209 sizeCy << 0.01, 0.25;
213 BOOST_CHECK(geom.size == sizeCy);
215 BOOST_CHECK(geom.geomInertia.isApprox(inertTest));
218 bodyTest =
graph.mapOfBodies.at(
"bodyBox");
219 mass = 1000 * 0.02 * 0.02 * 0.5;
221 Eigen::Vector3d sizeB;
222 sizeB << 0.02, 0.02, .5;
226 BOOST_CHECK(geom.size == sizeB);
228 BOOST_CHECK(geom.geomInertia.isApprox(inertTest));
231 bodyTest =
graph.mapOfBodies.at(
"bodyCapsule");
232 mass = 1000 * (4.0 / 3 * pi * std::pow(0.01, 3) + 2 * pi * std::pow(0.01, 2) * 0.25);
234 Eigen::Vector2d sizeCa;
235 sizeCa << 0.01, 0.25;
239 BOOST_CHECK(geom.size == sizeCa);
241 BOOST_CHECK(geom.geomInertia.isApprox(inertTest));
244 bodyTest =
graph.mapOfBodies.at(
"bodySphere");
245 mass = 1000 * 4.0 / 3 * pi * std::pow(0.01, 3);
247 Eigen::VectorXd sizeS(1);
252 BOOST_CHECK(geom.size == sizeS);
254 BOOST_CHECK(geom.geomInertia.isApprox(inertTest));
257 bodyTest =
graph.mapOfBodies.at(
"bodyEllip");
258 mass = 1000 * 4.0 / 3 * pi * 0.01 * 0.01 * 0.25;
260 Eigen::Vector3d sizeEl;
261 sizeEl << 0.01, 0.01, 0.25;
265 BOOST_CHECK(geom.size == sizeEl);
267 BOOST_CHECK(geom.geomInertia.isApprox(inertTest));
276 std::istringstream xmlData(R
"(<mujoco model="inertiaFromGeom">
277 <compiler inertiafromgeom="true" />
279 <body pos="0 0 0" name="body0">
280 <geom type="box" size=".01 .01 .01" pos="0 0 0.01"/>
281 <geom type="box" size=".01 .01 .01" pos="0 0 0.03"/>
288 typedef ::pinocchio::mjcf::details::MjcfGraph MjcfGraph;
292 MjcfGraph
graph(visitor,
"fakeMjcf");
293 graph.parseGraphFromXML(namefile.name());
294 graph.parseRootTree();
299 double massBigBox = 1000 * 0.02 * 0.02 * 0.04;
305 inertBigBox = placementBigBox.act(inertBigBox);
307 BOOST_CHECK(inertBigBox.isApprox(inertBody));
317 std::istringstream xmlData(R
"(
318 <compiler angle="radian" eulerseq="xyz"/>
319 <quaternion pos="0.3 0.2 0.5" quat="1 -1 0 0"/>
320 <axis pos="0.3 0.2 0.5" axisangle="-1 0 0 1.5707963"/>
321 <euler pos="0.3 0.2 0.5" euler="-1.57079633 0 0"/>
322 <xyaxes pos="0.3 0.2 0.5" xyaxes="1 0 0 0 0 -1"/>
323 <zaxis pos="0.3 0.2 0.5" zaxis="0 1 0"/>
328 boost::property_tree::read_xml(xmlData, pt);
330 typedef ::pinocchio::mjcf::details::MjcfGraph MjcfGraph;
334 MjcfGraph
graph(visitor,
"fakeMjcf");
336 graph.parseCompiler(pt.get_child(
"compiler"));
344 Matrix3 rotation_matrix;
345 rotation_matrix << 1., 0., 0., 0., 0., 1., 0., -1., 0.;
349 BOOST_CHECK(placement_q.isApprox(real_placement, 1e-7));
350 BOOST_CHECK(placement_e.isApprox(real_placement, 1e-7));
351 BOOST_CHECK(placement_a.isApprox(real_placement, 1e-7));
352 BOOST_CHECK(placement_xy.isApprox(real_placement, 1e-7));
353 BOOST_CHECK(placement_z.isApprox(real_placement, 1e-7));
360 namespace pt = boost::property_tree;
361 std::istringstream xmlIn(R
"(
363 <default class="mother">
364 <joint A="a0" B="b0" />
366 <default class="layer1">
367 <joint A="a1" C="c1" />
368 <default class="layer2">
373 <default class="layerP">
382 pt::read_xml(xmlIn, ptr, pt::xml_parser::trim_whitespace);
384 typedef ::pinocchio::mjcf::details::MjcfGraph MjcfGraph;
388 MjcfGraph
graph(visitor,
"fakeMjcf");
389 graph.parseDefault(ptr.get_child(
"default"), ptr,
"default");
391 std::unordered_map<std::string, pt::ptree> TrueMap;
393 std::istringstream xml1(R
"(<default class="mother">
394 <joint A="a0" B="b0" />
396 <default class="layer1">
397 <joint A="a1" C="c1" />
398 <default class="layer2">
403 <default class="layerP">
409 pt::read_xml(xml1, p1, pt::xml_parser::trim_whitespace);
413 std::istringstream xml2(R
"(<default class="layer1">
414 <joint A="a1" B="b0" C="c1" />
415 <default class="layer2">
422 pt::read_xml(xml2, p2, pt::xml_parser::trim_whitespace);
425 std::string
name =
"layer1";
426 TrueMap.insert(std::make_pair(
name, p2.get_child(
"default")));
428 std::istringstream xml3(R
"(<default class="layer2">
429 <joint A="a1" B="b2" C="c1"/>
430 <geom A="a0" C="c2"/>
433 pt::read_xml(xml3, p3, pt::xml_parser::trim_whitespace);
437 std::istringstream xml4(R
"(<default class="layerP">
438 <joint A="a0" B="b0" K="b2"/>
443 pt::read_xml(xml4, p4, pt::xml_parser::trim_whitespace);
448 #ifdef PINOCCHIO_WITH_URDFDOM
461 std::string file_u =
PINOCCHIO_MODEL_DIR + std::string(
"/../unittest/models/test_mjcf.urdf");
472 for (
size_t i = 0;
i < size_t(model_m.
njoints);
i++)
475 #endif // PINOCCHIO_WITH_URDFDOM
481 std::istringstream xmlDataNoStrip(R
"(<mujoco model="parseDirs">
482 <compiler meshdir="meshes" texturedir="textures"/>
484 <texture name="testTexture" file="texture.png" type="2d"/>
485 <material name="matTest" texture="testTexture"/>
486 <mesh file="C:/auto/mesh.obj"/>
490 std::istringstream xmlDataNoStrip(R
"(<mujoco model="parseDirs">
491 <compiler meshdir="meshes" texturedir="textures"/>
493 <texture name="testTexture" file="texture.png" type="2d"/>
494 <material name="matTest" texture="testTexture"/>
495 <mesh file="/auto/mesh.obj"/>
502 typedef ::pinocchio::mjcf::details::MjcfGraph MjcfGraph;
506 MjcfGraph
graph(visitor,
"/fakeMjcf/fake.xml");
507 graph.parseGraphFromXML(namefile.name());
511 BOOST_CHECK_EQUAL(text.
textType,
"2d");
516 BOOST_CHECK_EQUAL(
mat.texture,
"testTexture");
530 std::istringstream xmlDataNoStrip(R
"(<mujoco model="parseDirs">
531 <compiler meshdir="meshes" texturedir="textures" strippath="true"/>
533 <mesh file="/auto/mesh.obj"/>
539 typedef ::pinocchio::mjcf::details::MjcfGraph MjcfGraph;
543 MjcfGraph
graph(visitor,
"/fakeMjcf/fake.xml");
544 graph.parseGraphFromXML(namefile.name());
558 std::istringstream xmlData(R
"(
559 <mujoco model="model_RX">
562 <body name="link1" pos="0 0 0">
563 <joint name="joint1" type="hinge" axis="1 0 0"/>
571 typedef ::pinocchio::mjcf::details::MjcfGraph MjcfGraph;
575 MjcfGraph
graph(visitor,
"fakeMjcf");
576 graph.parseGraphFromXML(namefile.name());
577 graph.parseRootTree();
585 for (
size_t i = 0;
i < size_t(model_m.
njoints);
i++)
595 std::istringstream xmlData(R
"(
596 <mujoco model="model_PX">
599 <body name="link1" pos="0 0 0">
600 <joint name="joint1" type="slide" axis="1 0 0"/>
608 typedef ::pinocchio::mjcf::details::MjcfGraph MjcfGraph;
612 MjcfGraph
graph(visitor,
"fakeMjcf");
613 graph.parseGraphFromXML(namefile.name());
614 graph.parseRootTree();
622 for (
size_t i = 0;
i < size_t(model_m.
njoints);
i++)
632 std::istringstream xmlData(R
"(
633 <mujoco model="model_Sphere">
636 <body name="link1" pos="0 0 0">
637 <joint name="joint1" type="ball"/>
645 typedef ::pinocchio::mjcf::details::MjcfGraph MjcfGraph;
649 MjcfGraph
graph(visitor,
"fakeMjcf");
650 graph.parseGraphFromXML(namefile.name());
651 graph.parseRootTree();
659 for (
size_t i = 0;
i < size_t(model_m.
njoints);
i++)
669 std::istringstream xmlData(R
"(
670 <mujoco model="model_Free">
673 <body name="link1" pos="0 0 0">
674 <freejoint name="joint1"/>
682 typedef ::pinocchio::mjcf::details::MjcfGraph MjcfGraph;
686 MjcfGraph
graph(visitor,
"fakeMjcf");
687 graph.parseGraphFromXML(namefile.name());
688 graph.parseRootTree();
696 for (
size_t i = 0;
i < size_t(model_m.
njoints);
i++)
706 std::istringstream xmlData(R
"(
707 <mujoco model="composite_RXRY">
710 <body name="link1" pos="0 0 0">
711 <joint name="joint1" type="hinge" axis="1 0 0"/>
712 <joint name="joint2" type="hinge" axis="0 1 0"/>
720 typedef ::pinocchio::mjcf::details::MjcfGraph MjcfGraph;
724 MjcfGraph
graph(visitor,
"fakeMjcf");
725 graph.parseGraphFromXML(namefile.name());
726 graph.parseRootTree();
738 for (
size_t i = 0;
i < size_t(model_m.
njoints);
i++)
748 std::istringstream xmlData(R
"(
749 <mujoco model="composite_PXPY">
752 <body name="link1" pos="0 0 0">
753 <joint name="joint1" type="slide" axis="1 0 0"/>
754 <joint name="joint2" type="slide" axis="0 1 0"/>
762 typedef ::pinocchio::mjcf::details::MjcfGraph MjcfGraph;
766 MjcfGraph
graph(visitor,
"fakeMjcf");
767 graph.parseGraphFromXML(namefile.name());
768 graph.parseRootTree();
780 for (
size_t i = 0;
i < size_t(model_m.
njoints);
i++)
790 std::istringstream xmlData(R
"(
791 <mujoco model="composite_PXRY">
794 <body name="link1" pos="0 0 0">
795 <joint name="joint1" type="slide" axis="1 0 0"/>
796 <joint name="joint2" type="hinge" axis="0 1 0"/>
804 typedef ::pinocchio::mjcf::details::MjcfGraph MjcfGraph;
808 MjcfGraph
graph(visitor,
"fakeMjcf");
809 graph.parseGraphFromXML(namefile.name());
810 graph.parseRootTree();
822 for (
size_t i = 0;
i < size_t(model_m.
njoints);
i++)
832 std::istringstream xmlData(R
"(
833 <mujoco model="composite_PXSphere">
836 <body name="link1" pos="0 0 0">
837 <joint name="joint1" type="slide" axis="1 0 0"/>
838 <joint name="joint2" type="ball"/>
846 typedef ::pinocchio::mjcf::details::MjcfGraph MjcfGraph;
850 MjcfGraph
graph(visitor,
"fakeMjcf");
851 graph.parseGraphFromXML(namefile.name());
852 graph.parseRootTree();
864 for (
size_t i = 0;
i < size_t(model_m.
njoints);
i++)
880 q << 1.57079633, 0.3, 0.5;
886 Eigen::Matrix3d refOrient;
887 refOrient << 0, -.9553, .2955, 1, 0, 0, 0, .2955, .9553;
889 pos << .8522, 2, 0.5223;
890 BOOST_CHECK(pinPos.isApprox(
SE3(refOrient,
pos), 1e-4));
892 f_id =
model.getFrameId(
"body2");
893 pinPos =
data.oMf[f_id];
895 refOrient << 0, -.9553, .2955, 1, 0, 0, 0, .2955, .9553;
897 pos << .8522, 4, 0.5223;
898 BOOST_CHECK(pinPos.isApprox(
SE3(refOrient,
pos), 1e-4));
904 std::istringstream xmlData(R
"(
905 <mujoco model="testKeyFrame">
907 <position ctrllimited="true" ctrlrange="-.1 .1" kp="30"/>
908 <default class="joint">
909 <geom type="cylinder" size=".006" fromto="0 0 0 0 0 .05" rgba=".9 .6 1 1"/>
915 <geom type="capsule" size=".01" fromto="0 0 0 .2 0 0"/>
916 <body pos=".2 0 0" name="body2">
917 <joint type="ball" damping=".1"/>
918 <geom type="capsule" size=".01" fromto="0 -.15 0 0 0 0"/>
925 0.988015 0 0.154359 0
926 0.988015 0 0.154359 0"/>
937 Eigen::VectorXd vect_ref(model_m.
nq);
938 vect_ref << 0, 0, 0.596, 0, 0.154359, 0, 0.988015, 0, 0.154359, 0, 0.988015;
940 BOOST_CHECK(vect_model.size() == vect_ref.size());
941 BOOST_CHECK(vect_model == vect_ref);
950 std::istringstream xmlData(R
"(
951 <mujoco model="testJointInertia">
955 <inertial mass="0.629769" pos="-0.041018 -0.00014 0.049974"
956 diaginertia="0.00315 0.00388 0.004285"/>
968 Matrix3 inertia_matrix = Eigen::Matrix3d::Zero();
969 inertia_matrix(0, 0) = 0.00315;
970 inertia_matrix(1, 1) = 0.00388;
971 inertia_matrix(2, 2) = 0.004285;
974 BOOST_CHECK(model_m.
inertias[1].isApprox(real_inertia));
981 std::cout <<
" Armature ------------ " << std::endl;
982 std::istringstream xmlData(R
"(
983 <mujoco model="model_RX">
985 <joint armature="1" damping="1" limited="true"/>
989 <body name="link1" pos="0 0 0">
990 <joint name="joint1" type="hinge" axis="1 0 0" armature="1.3"/>
991 <joint name="joint2" type="hinge" axis="0 1 0" armature="2.4"/>
992 <joint name="joint3" type="hinge" axis="0 0 1" armature="0.4"/>
993 <body pos=".2 0 0" name="body2">
1003 typedef ::pinocchio::mjcf::details::MjcfGraph MjcfGraph;
1007 MjcfGraph
graph(visitor,
"fakeMjcf");
1008 graph.parseGraphFromXML(namefile.name());
1009 graph.parseRootTree();
1011 Eigen::VectorXd armature_real(model_m.
nv);
1012 armature_real << 1.3, 2.4, 0.4, 1, 1, 1;
1014 for (
size_t i = 0;
i < size_t(model_m.
nv);
i++)
1015 BOOST_CHECK_EQUAL(model_m.
armature[
i], armature_real[
i]);
1021 std::istringstream xmlData(R
"(
1022 <mujoco model="testRefPose">
1023 <compiler angle="radian"/>
1026 <body pos=".2 0 0" name="body2">
1027 <joint type="slide" ref="0.14"/>
1028 <body pos=".2 0 0" name="body3">
1029 <joint type="hinge" ref="0.1"/>
1035 <key name="test" qpos=".8 .5"/>
1045 Eigen::VectorXd vect_ref(model_m.
nq);
1046 vect_ref << 0.66, 0.4;
1048 BOOST_CHECK(vect_model.size() == vect_ref.size());
1049 BOOST_CHECK(vect_model == vect_ref);
1055 std::istringstream xmlData(R
"(
1056 <mujoco model="keyframeComposite">
1057 <compiler angle="radian"/>
1060 <body pos=".2 0 0" name="body2">
1061 <joint type="slide"/>
1062 <joint type="hinge"/>
1063 <body pos=".2 0 0" name="body3">
1064 <joint type="hinge"/>
1070 <key name="test" qpos=".8 .5 .5"/>
1080 Eigen::VectorXd vect_ref(model_m.
nq);
1081 vect_ref << 0.8, 0.5, 0.5;
1083 BOOST_CHECK(vect_model.size() == vect_ref.size());
1084 BOOST_CHECK(vect_model == vect_ref);
1093 std::istringstream xmlData(R
"(
1094 <mujoco model="site">
1095 <compiler angle="radian"/>
1098 <body pos=".2 0 0" name="body2">
1099 <joint type="hinge"/>
1100 <body pos=".2 0 0" name="body3">
1101 <joint type="hinge"/>
1102 <site name="testSite" pos="0.03 0 -0.05"/>
1116 Matrix3 rotation_matrix;
1117 rotation_matrix << 1., 0., 0., 0., 1., 0., 0., 0., 1.;
1120 BOOST_CHECK(model_m.
frames[model_m.
getFrameId(
"testSite")].placement.isApprox(real_placement));
1133 BOOST_CHECK_EQUAL(model_m.
nq, 29);
1143 BOOST_CHECK(
model.names[1] ==
"root_joint");
1146 const std::string name_ =
"freeFlyer_joint";
1148 BOOST_CHECK(model_name.
names[1] == name_);
1151 #ifdef PINOCCHIO_WITH_URDFDOM
1164 const std::string filename_urdf =
PINOCCHIO_MODEL_DIR + std::string(
"/simple_humanoid.urdf");
1169 BOOST_CHECK(model_urdf.
nq == model_m.
nq);
1170 BOOST_CHECK(model_urdf.
nv == model_m.
nv);
1176 BOOST_CHECK(model_urdf.
names == model_m.
names);
1179 BOOST_CHECK(model_urdf.
name == model_m.
name);
1181 BOOST_CHECK(model_urdf.
nqs == model_m.
nqs);
1183 BOOST_CHECK(model_urdf.
nvs == model_m.
nvs);
1186 typename ConfigVectorMap::const_iterator it_model_urdf =
1190 std::advance(
it, k);
1191 std::advance(it_model_urdf, k);
1192 BOOST_CHECK(
it->second.size() == it_model_urdf->second.size());
1193 BOOST_CHECK(
it->second == it_model_urdf->second);
1202 BOOST_CHECK(model_urdf.
damping.size() == model_m.
damping.size());
1224 for (
size_t k = 1; k < model_m.
inertias.size(); ++k)
1236 BOOST_CHECK(model_urdf.
frames.size() == model_m.
frames.size());
1237 for (
size_t k = 1; k < model_urdf.
frames.size(); ++k)
1239 BOOST_CHECK(model_urdf.
frames[k] == model_m.
frames[k]);
1242 #endif // PINOCCHIO_WITH_URDFDOM
1244 #if defined(PINOCCHIO_WITH_HPP_FCL)
1251 std::istringstream xmlData(R
"(<mujoco model="inertiaFromGeom">
1252 <compiler inertiafromgeom="true" />
1254 <body pos="0 0 0" name="bodyCylinder">
1255 <geom type="cylinder" size=".01 0.25" pos="0 0 0" quat="1 0 0 0"/>
1256 <body pos="0 0 0" name="bodyBox">
1257 <geom type="box" size=".01 0.01 0.25" pos="0 0 0" quat="1 0 0 0"/>
1259 <body pos="0 0 0" name="bodyCapsule">
1260 <geom type="capsule" size=".01 0.25" pos="0 0 0" quat="1 0 0 0"/>
1262 <body pos="0 0 0" name="bodySphere">
1263 <geom type="sphere" size=".01" pos="0 0 0" quat="1 0 0 0"/>
1265 <body pos="0 0 0" name="bodyEllip">
1266 <geom type="ellipsoid" size=".01 0.01 0.25" pos="0 0 0" quat="1 0 0 0"/>
1280 BOOST_CHECK(geomModel_m.
ngeoms == 5);
1284 BOOST_CHECK(cyl->halfLength == 0.25);
1285 BOOST_CHECK(cyl->radius == 0.01);
1289 BOOST_CHECK(cap->halfLength == 0.25);
1290 BOOST_CHECK(cap->radius == 0.01);
1294 BOOST_CHECK(s->radius == 0.01);
1298 Eigen::Vector3d sides;
1299 sides << 0.01, 0.01, 0.25;
1300 BOOST_CHECK(
b->halfSide == sides);
1304 BOOST_CHECK(e->radii == sides);
1306 #endif // if defined(PINOCCHIO_WITH_HPP_FCL)
1327 BOOST_CHECK(
cm.joint2_placement.isApprox(
cm.joint1_placement.inverse()));
1331 BOOST_AUTO_TEST_SUITE_END()