Skip to content
New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

fix missing nearest points in Octree<->Mesh distance result #427

Merged
Merged
Show file tree
Hide file tree
Changes from 2 commits
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
Original file line number Diff line number Diff line change
Expand Up @@ -506,7 +506,7 @@ bool OcTreeSolver<NarrowPhaseSolver>::OcTreeMeshDistanceRecurse(const OcTree<S>*
Vector3<S> closest_p1, closest_p2;
solver->shapeTriangleDistance(box, box_tf, p1, p2, p3, tf2, &dist, &closest_p1, &closest_p2);

dresult->update(dist, tree1, tree2, root1 - tree1->getRoot(), primitive_id);
dresult->update(dist, tree1, tree2, root1 - tree1->getRoot(), primitive_id, closest_p1, closest_p2);

return drequest->isSatisfied(*dresult);
}
Expand Down
20 changes: 20 additions & 0 deletions test/test_fcl_octomap_distance.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -65,6 +65,8 @@ void octomap_distance_test_BVH(std::size_t n, double resolution = 0.1);
template <typename S>
void test_octomap_distance()
{
// -- compares result of (manager of primitives <-> octomap)
// against (manager of primitives <-> manager of box primitives from octomap)
#ifdef NDEBUG
octomap_distance_test<S>(200, 100, false, false);
octomap_distance_test<S>(200, 1000, false, false);
Expand All @@ -83,6 +85,8 @@ GTEST_TEST(FCL_OCTOMAP, test_octomap_distance)
template <typename S>
void test_octomap_distance_mesh()
{
// -- compares result of (manager of meshes <-> octomap)
// against (manager of meshes <-> manager of box meshes from octomap)
#ifdef NDEBUG
octomap_distance_test<S>(200, 100, true, true);
octomap_distance_test<S>(200, 1000, true, true);
Expand All @@ -101,6 +105,8 @@ GTEST_TEST(FCL_OCTOMAP, test_octomap_distance_mesh)
template <typename S>
void test_octomap_distance_mesh_octomap_box()
{
// -- compares result of (manager of meshes <-> octomap)
// against (manager of meshes <-> manager of box primitives from octomap)
#ifdef NDEBUG
octomap_distance_test<S>(200, 100, true, false);
octomap_distance_test<S>(200, 1000, true, false);
Expand Down Expand Up @@ -219,6 +225,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);

std::cout << "cdata, np0:\n" << cdata.result.nearest_points[0] << std::endl;
std::cout << "cdata, np1:\n" << cdata.result.nearest_points[1] << std::endl;
std::cout << "cdata2, np0:\n" << cdata2.result.nearest_points[0] << std::endl;
std::cout << "cdata2, np1:\n" << cdata2.result.nearest_points[1] << std::endl;
EXPECT_NEAR((cdata.result.nearest_points[0] - cdata2.result.nearest_points[1]).norm(), 0.0, 1e-6);
EXPECT_NEAR((cdata.result.nearest_points[1] - cdata2.result.nearest_points[0]).norm(), 0.0, 1e-6);
}
}

Expand Down Expand Up @@ -294,6 +307,13 @@ void octomap_distance_test(S env_scale, std::size_t env_size, bool use_mesh, boo
else
EXPECT_TRUE(std::abs(cdata.result.min_distance - cdata2.result.min_distance) < 1e-3);

std::cout << "cdata, np0:\n" << cdata.result.nearest_points[0] << std::endl;
std::cout << "cdata, np1:\n" << cdata.result.nearest_points[1] << std::endl;
std::cout << "cdata2, np0:\n" << cdata2.result.nearest_points[0] << std::endl;
std::cout << "cdata2, np1:\n" << cdata2.result.nearest_points[1] << std::endl;
EXPECT_NEAR((cdata.result.nearest_points[0] - cdata2.result.nearest_points[0]).norm(), 0.0, 1e-6);
EXPECT_NEAR((cdata.result.nearest_points[1] - cdata2.result.nearest_points[1]).norm(), 0.0, 1e-6);

delete manager;
delete manager2;
for(size_t i = 0; i < boxes.size(); ++i)
Expand Down