18 #include <boost/test/unit_test.hpp>
25 typedef std::map<std::pair<std::string, std::string>, fcl::DistanceResult>
PairDistanceMap_t;
33 BOOST_AUTO_TEST_SUITE(BOOST_TEST_MODULE)
44 model.addJointFrame(idx);
50 model.addJointFrame(idx);
54 std::shared_ptr<fcl::Box> sample(
new fcl::Box(1, 1, 1));
58 "ff1_collision_object", joint_parent_1,
model.getBodyId(
"planar1_body"),
SE3::Identity(),
59 sample,
"", Eigen::Vector3d::Ones()));
62 std::shared_ptr<fcl::Box> sample2(
new fcl::Box(1, 1, 1));
67 "ff2_collision_object", joint_parent_2,
model.getBodyId(
"planar2_body"),
SE3::Identity(),
68 sample2,
"", Eigen::Vector3d::Ones()),
73 std::shared_ptr<fcl::Box> universe_body_geometry(
new fcl::Box(1, 1, 1));
80 "universe_collision_object", joint_parent_3,
model.getBodyId(
"universe_body"),
81 universe_body_placement, universe_body_geometry,
"", Eigen::Vector3d::Ones()),
93 std::cout <<
"------ Model ------ " << std::endl;
95 std::cout <<
"------ Geom ------ " << std::endl;
96 std::cout << geomModel;
97 std::cout <<
"------ DataGeom ------ " << std::endl;
98 std::cout << geomData;
100 Eigen::VectorXd
q(
model.nq);
101 q << 0, 0, 1, 0, 0, 0, 1, 0;
104 BOOST_CHECK(geomData.oMg[idx_geom3].isApprox(universe_body_placement));
107 q << 2, 0, 1, 0, 0, 0, 1, 0;
112 q << 0.99, 0, 1, 0, 0, 0, 1, 0;
117 q << 1.01, 0, 1, 0, 0, 0, 1, 0;
122 geomModel.removeGeometryObject(
"ff2_collision_object");
125 BOOST_CHECK(geomModel.ngeoms == 2);
126 BOOST_CHECK(geomModel.geometryObjects.size() == 2);
127 BOOST_CHECK(geomModel.collisionPairs.size() == 1);
129 (geomModel.collisionPairs[0].first == 0 && geomModel.collisionPairs[0].second == 1)
130 || (geomModel.collisionPairs[0].first == 1 && geomModel.collisionPairs[0].second == 0));
131 BOOST_CHECK(geomData.activeCollisionPairs.size() == 1);
132 BOOST_CHECK(geomData.distanceRequests.size() == 1);
133 BOOST_CHECK(geomData.distanceResults.size() == 1);
134 BOOST_CHECK(geomData.distanceResults.size() == 1);
135 BOOST_CHECK(geomData.collisionResults.size() == 1);
138 #if defined(PINOCCHIO_WITH_URDFDOM)
148 + std::string(
"/example-robot-data/robots/romeo_description/urdf/romeo_small.urdf");
149 std::vector<std::string> packageDirs;
151 packageDirs.push_back(meshDir);
161 BOOST_CHECK(geomModelOther == geomModel);
165 fcl::CollisionResult result;
167 Eigen::VectorXd
q(
model.nq);
168 q << 0, 0, 0.840252, 0, 0, 0, 1, 0, 0, -0.3490658, 0.6981317, -0.3490658, 0, 0, 0, -0.3490658,
169 0.6981317, -0.3490658, 0, 0, 1.5, 0.6, -0.5, -1.05, -0.4, -0.3, -0.2, 0, 0, 0, 0, 1.5, -0.6,
170 0.5, 1.05, -0.4, -0.3, -0.2;
176 fcl::DistanceResult distance_res =
computeDistance(geomModel, geomData, idx);
177 BOOST_CHECK(distance_res.min_distance > 0.);
189 + std::string(
"/example-robot-data/robots/romeo_description/urdf/romeo_small.urdf");
190 std::vector<std::string> packageDirs;
192 packageDirs.push_back(meshDir);
195 + std::string(
"/example-robot-data/robots/romeo_description/srdf/romeo.srdf");
208 Eigen::VectorXd
q =
model.referenceConfigurations[
"half_sitting"];
215 for (
size_t cp_index = 0; cp_index <
geom_model.collisionPairs.size(); ++cp_index)
234 BOOST_CHECK(!
res.isCollision());
254 + std::string(
"/example-robot-data/robots/romeo_description/urdf/romeo_small.urdf");
255 std::vector<std::string> packageDirs;
257 packageDirs.push_back(meshDir);
260 + std::string(
"/example-robot-data/robots/romeo_description/srdf/romeo.srdf");
273 Eigen::VectorXd
q =
model.referenceConfigurations[
"half_sitting"];
294 + std::string(
"/example-robot-data/robots/romeo_description/urdf/romeo_small.urdf");
295 std::vector<std::string> packageDirs;
297 packageDirs.push_back(meshDir);
308 BOOST_CHECK(geom_model2.
ngeoms == 2 * geom_model1.
ngeoms);
322 BOOST_CHECK(geom_model_empty.
ngeoms == 0);
330 std::vector<std::string> packageDirs;
334 + std::string(
"/example-robot-data/robots/romeo_description/urdf/romeo_small.urdf");
336 packageDirs.push_back(meshDir);
347 BOOST_FOREACH (
double radius, geomData.radius)
348 BOOST_CHECK(
radius >= 0.);
350 #endif // if defined(PINOCCHIO_WITH_URDFDOM)
352 BOOST_AUTO_TEST_SUITE_END()