diff --git a/test/test_fcl_octomap_distance.cpp b/test/test_fcl_octomap_distance.cpp index db430ce81..3a5e6880d 100644 --- a/test/test_fcl_octomap_distance.cpp +++ b/test/test_fcl_octomap_distance.cpp @@ -196,6 +196,7 @@ void octomap_distance_test_BVH(std::size_t n, double resolution) CollisionObject obj1(m1_ptr, tf); CollisionObject obj2(tree_ptr, tf); test::DistanceData cdata; + cdata.request.enable_nearest_points = true; S dist1 = std::numeric_limits::max(); test::defaultDistanceFunction(&obj1, &obj2, &cdata, dist1); @@ -219,6 +220,13 @@ void octomap_distance_test_BVH(std::size_t n, double resolution) std::cout << dist1 << " " << dist2 << std::endl; EXPECT_TRUE(std::abs(dist1 - dist2) < 0.001); + + // Check that the nearest points are consistent with the distance + // Note that we cannot compare the result with the "boxes" approximation, + // since the problem is ill-posed (i.e. the nearest points may differ widely + // for slightly different geometries) + Vector3 nearestPointDistance = cdata.result.nearest_points[0] - cdata.result.nearest_points[1]; + EXPECT_NEAR(nearestPointDistance.norm(), dist1, 0.001); } }