35 #include <gtest/gtest.h>
42 #include "fcl_resources/config.h"
53 const S radius_1 = 20;
54 const S radius_2 = 10;
71 distance(&s1, tf1, &s2, tf2, request, result);
87 distance(&s1, tf1, &s2, tf2, request, result);
102 distance(&s1, tf1, &s2, tf2, request, result);
105 (tf1.translation() - tf2.translation()).norm() - radius_1 - radius_2;
111 Vector3<S> dir = (tf2.translation() - tf1.translation()).normalized();
114 distance_tolerance));
115 Vector3<S> p1_expected = tf2.translation() - dir * radius_2;
117 distance_tolerance));
121 template <
typename S>
140 distance(&s1, tf1, &s2, tf2, request, result);
150 distance(&s1, tf1, &s2, tf2, request, result);
157 ASSERT_NEAR(result.
min_distance, -5, distance_tolerance);
162 distance_tolerance * 100));
164 distance_tolerance * 100));
169 template <
typename S>
179 using CollisionGeometryPtr_t = std::shared_ptr<fcl::CollisionGeometry<S>>;
180 const S cylinder_radius = 0.03;
181 const S cylinder_length = 0.65;
182 CollisionGeometryPtr_t cylinder_geo(
185 X_WC.translation() << 0.6, 0, 0.325;
188 const S sphere_radius = 0.055;
189 CollisionGeometryPtr_t sphere_geo(
new fcl::Sphere<S>(sphere_radius));
192 X_WS.matrix() << -0.9954758066, -0.0295866301, 0.0902914702, 0.5419794018,
193 -0.0851034786, -0.1449450565, -0.9857729599, -0.0621175025,
194 0.0422530022, -0.9889972506, 0.1417713719, 0.6016236576,
205 ASSERT_NO_THROW(
fcl::distance(&cylinder, &sphere, request, result));
212 EXPECT_LE(abs(p_CPc(2)), cylinder_length / 2);
213 EXPECT_LE(p_CPc.template head<2>().norm(), cylinder_radius);
217 EXPECT_LE(p_SPs.norm(), sphere_radius);
220 template <
typename S>
225 using CollisionGeometryPtr_t = std::shared_ptr<fcl::CollisionGeometryd>;
226 CollisionGeometryPtr_t cylinder_geo(
230 CollisionGeometryPtr_t box_geo(
231 new fcl::Box<S>(box_size(0), box_size(1), box_size(2)));
240 ASSERT_NO_THROW(
fcl::distance(&cylinder, &box, request, result));
248 EXPECT_LE(abs(p_CPc(2)), cylinder_length / 2 + tol);
249 EXPECT_LE(p_CPc.template head<2>().norm(), cylinder_radius);
253 EXPECT_TRUE((p_BPb.array().abs() <= box_size.array() / 2 + tol).all());
256 template <
typename S>
263 S cylinder_radius = 0.05;
264 S cylinder_length = 0.06;
267 X_WC.matrix() << -0.99999999997999022838, 6.2572835802045040178e-10,
268 6.3260669852976095481e-06, 0.57500009756757608503,
269 6.3260669851683709551e-06, -6.3943303429958554955e-10,
270 0.99999999997999056145, -0.42711963046787942977,
271 6.2573180158128459924e-10, 1, 6.3942912945996747041e-10,
272 1.1867093358746836351, 0, 0, 0, 1;
276 X_WB.matrix() << 0, -1, 0, 0.8,
285 X_WC.matrix() << -0.97313010759279283679, -0.12202804064972551379,
286 0.19526123781136842106, 0.87472781461138560122, 0.20950801135757171623,
287 -0.11745920593569325607, 0.97072639199619581429, -0.4038687881347159947,
288 -0.095520609678929752073, 0.98555187191549953329, 0.13986894183635001365,
289 1.5871328698116491385, 0, 0, 0, 1;
291 X_WB.matrix() << 0, -1, 0, 0.8,
300 template <
typename S>
306 using CollisionGeometryPtr_t = std::shared_ptr<fcl::CollisionGeometryd>;
307 CollisionGeometryPtr_t box1_geo(
308 new fcl::Box<S>(box1_size(0), box1_size(1), box1_size(2)));
311 CollisionGeometryPtr_t box2_geo(
312 new fcl::Box<S>(box2_size(0), box2_size(1), box2_size(2)));
321 ASSERT_NO_THROW(
fcl::distance(&box1, &box2, request, result));
329 const double tol_1 = tol *
std::max(S(1), (box1_size / 2).maxCoeff());
331 (p_B1P1.array().abs() <= (box1_size / 2).array() + tol_1).all())
332 <<
"\n p_B1P1: " << p_B1P1.transpose()
333 <<
"\n box1_size / 2: " << (box1_size / 2).transpose()
334 <<
"\n tol: " << tol_1;
337 const double tol_2 = tol *
std::max(S(1), (box2_size / 2).maxCoeff());
340 (p_B2P2.array().abs() <= (box2_size / 2).array() + tol_2).all())
341 <<
"\n p_B2P2: " << p_B2P2.transpose()
342 <<
"\n box2_size / 2: " << (box2_size / 2).transpose()
343 <<
"\n tol: " << tol_2;
356 template <
typename S>
358 SCOPED_TRACE(
"test_distance_box_box_regression1");
361 X_WB1.matrix() << -3.0627937852578681533e-08, -0.99999999999999888978,
362 -2.8893865161583314238e-08, 0.63499979627350811029, 0.9999999999999980016,
363 -3.0627939739957803544e-08, 6.4729926918527511769e-08,
364 -0.48500002215636439651, -6.4729927722963847085e-08,
365 -2.8893863029448751323e-08, 0.99999999999999711342, 1.0778146458339641356,
368 const Vector3<S> box2_size(0.025, 0.35, 1.845);
371 X_WB2.matrix() << 0, -1, 0, 0.8,
382 template <
typename S>
384 SCOPED_TRACE(
"test_distance_box_box_regression2");
387 X_WB1.matrix() << 1,0,0, -0.72099999999999997424,
388 0,1,0, -0.77200000000000001954,
389 0,0,1, 0.81000000000000005329,
392 const Vector3<S> box2_size(0.049521, 0.146, 0.0725);
395 X_WB2.matrix() << 0.10758262492983036718, -0.6624881850015212903, -0.74130653817877356637, -0.42677133002999478872,
396 0.22682184885125472595, -0.709614040775253474, 0.6670830248314786326, -0.76596851247746788882,
397 -0.96797615037608542021, -0.23991106241273435495, 0.07392465377049164954, 0.80746731400091054098,
406 template <
typename S>
408 SCOPED_TRACE(
"test_distance_box_box_regression3");
412 X_WB1.matrix() << 4.8966386501092529215e-12, -1,0,-0.43999999999999994671,
413 1, 4.8966386501092529215e-12,0,-0.61499999999858001587,
414 0,0,1,0.35499999999999998224,
417 const Vector3<S> box2_size(0.035, 0.12, 0.03);
420 X_WB2.matrix() << 0.83512153565236335595, -0.55006546945762568868, -9.4542360608233572896e-16, -0.40653441507331000704,
421 0.55006546945762568868, 0.83512153565236313391, 1.1787444236552387666e-15, -0.69166166923735727945,
422 1.2902271444330665572e-16, -1.4878153530113264589e-15, 1, 0.43057093858718892276,
430 template <
typename S>
432 SCOPED_TRACE(
"test_distance_box_box_regression4");
435 X_WB1.translation() << -0.675, 0, 0.9115;
436 const Vector3<S> box2_size(0.494, 0.552, 0.01);
438 X_WB2.translation() << -0.692, 0, 0.935;
444 template <
typename S>
446 SCOPED_TRACE(
"test_distance_box_box_regression5");
449 X_WB1.translation() << -0.071000000000000035305, -0.77200000000000001954, 0.79999999999999993339;
452 X_WB2.translation() << 0.12099999999999999645, -0.78769605692727695523, 0.53422044196125151316;
456 template <
typename S>
458 SCOPED_TRACE(
"test_distance_box_box_regression6");
459 const Vector3<S> box1_size(0.31650000000000000355, 0.22759999999999999676, 0.1768000000000000127);
462 X_WB1.matrix() << 0.44540578475530234748, 0.89532881496493399442, -8.8937407685638678971e-09, 1.2652949075960071568,
463 -0.89532881496493377238, 0.44540578475530190339, -2.8948680226084145336e-08, 1.4551012423210101243,
464 -2.1957263975186326105e-08, 2.0856732016652919226e-08, 0.99999999999999955591, 0.49480006232932938204,
467 const Vector3<S> box2_size(0.49430000000000001714, 0.35460000000000002629, 0.075200000000000002953);
470 X_WB2.matrix() << 0.44171122913485860728, 0.8971572827861190591, -1.622764514865468214e-09, 1.1304016226141906376,
471 -0.8971572827861190591, 0.44171122913485860728, -5.1621053952306079594e-09, 1.8410802645284281009,
472 -3.9144271413829990148e-09, 3.7360349218094348098e-09, 1, 0.44400006232932492933,
488 template <
typename S>
490 SCOPED_TRACE(
"test_distance_box_box_regression_tilted_kissing_contact");
496 0.94096063217417758029, 0.29296840037289501035, 0.16959541586174811667,
497 -0.23569836841299879326, 0.92661523595848427348, -0.29296840037289506586,
498 -0.2429801799032638987, 0.23569836841299884878, 0.94096063217417758029;
500 for (
const S dim : {S(0.01), S(0.25), S(0.5), S(10), S(1000)}) {
505 X_WA.linear() = R_WF;
506 X_WA.translation() = p_WA;
508 X_WB.linear() = R_WF;
517 for (
const S
distance : {S(-1e-15), S(-2.5e-16), S(-1e-16), S(0), S(1e-16),
518 S(2.5e-16), S(1e-15)}) {
522 X_WB.translation() = p_WA + R_WF * p_AB_F;
523 SCOPED_TRACE(
"dim: " + std::to_string(dim) +
524 ", distance: " + std::to_string(
distance));
534 template <
typename S>
536 SCOPED_TRACE(
"test_distance_sphere_box_regression1");
537 using CollisionGeometryPtr_t = std::shared_ptr<fcl::CollisionGeometry<S>>;
538 const S sphere_radius = 0.06;
539 CollisionGeometryPtr_t sphere_geo(
new fcl::Sphere<S>(sphere_radius));
542 X_WS.matrix() << -0.99999999999999955591, -4.4637642593504144998e-09, 0, 1.7855056639081962376e-10,
543 4.4637642593504144998e-09, -0.99999999999999955591, 0, 0.039999999999999993894,
544 0, 0, 1.0000000000000008882, 0.33000000000000012657,
549 CollisionGeometryPtr_t box_geo(
new fcl::Box<S>(0.1, 0.1, 0.1));
552 X_WB.matrix() << 1, 0, 0, 0.05,
564 ASSERT_NO_THROW(
fcl::distance(&sphere, &box, request, result));
573 test_distance_spheresphere<double>(
GST_LIBCCD);
577 test_distance_spheresphere<double>(
GST_INDEP);
581 test_distance_spherecapsule<double>(
GST_LIBCCD);
585 test_distance_spherecapsule<double>(
GST_INDEP);
589 test_distance_cylinder_sphere1<double>();
593 test_distance_cylinder_box<double>();
599 test_distance_box_box_regression1<double>();
600 test_distance_box_box_regression2<double>();
601 test_distance_box_box_regression3<double>();
602 test_distance_box_box_regression4<double>();
603 test_distance_box_box_regression5<double>();
604 test_distance_box_box_regression6<double>();
605 test_distance_box_box_regression_tilted_kissing_contact<double>();
606 test_distance_sphere_box_regression1<double>();
610 int main(
int argc,
char* argv[])
612 ::testing::InitGoogleTest(&argc, argv);
613 return RUN_ALL_TESTS();