37 #include <gtest/gtest.h>
42 #include <geometric_shapes/body_operations.h>
43 #include <tf2_eigen/tf2_eigen.hpp>
44 #include <octomap/octomap.h>
49 static const double WIDTH = 1.0;
50 static const double HEIGHT = 1.0;
51 static const double DEPTH = 1.0;
52 static const double RESOLUTION = 0.1;
53 static const double ORIGIN_X = 0.0;
54 static const double ORIGIN_Y = 0.0;
55 static const double ORIGIN_Z = 0.0;
56 static const double MAX_DIST = 0.3;
64 return x * x + y * y + z * z;
69 for (
int z = 0; z < numZ; ++z)
71 for (
int y = 0; y < numY; ++y)
73 for (
int x = 0; x < numX; ++x)
81 for (
int z = 0; z < numZ; ++z)
83 for (
int y = 0; y < numY; ++y)
85 for (
int x = 0; x < numX; ++x)
98 for (
int z = 0; z < numZ; ++z)
100 for (
int y = 0; y < numY; ++y)
102 for (
int x = 0; x < numX; ++x)
146 std::cout <<
"Positive distance square ... negative distance square\n";
147 for (
int z = 0; z < numZ; ++z)
149 std::cout <<
"Z=" << z <<
'\n';
150 for (
int y = 0; y < numY; ++y)
152 for (
int x = 0; x < numX; ++x)
157 for (
int x = 0; x < numX; ++x)
162 for (
int x = 0; x < numX; ++x)
167 for (
int x = 0; x < numX; ++x)
199 printf(
"Cell %d %d %d neg distances not equal %d %d\n", x, y, z,
223 octomap::point3d query(qx, qy, qz);
224 octomap::OcTreeNode* result = octree.search(query);
236 octomap::point3d query_boundary(boundary_x, boundary_y, boundary_z);
237 result = octree.search(query_boundary);
247 std::cout <<
"No point at potential boundary query " << query.x() <<
' ' << query.y() <<
' ' << query.z()
252 if (!octree.isNodeOccupied(result))
254 std::cout <<
"Disagreement at " << qx <<
' ' << qy <<
' ' << qz <<
'\n';
266 unsigned int count = 0;
285 unsigned int count = 0;
286 for (octomap::OcTree::leaf_iterator it = octree.begin_leafs(), end = octree.end_leafs(); it != end; ++it)
288 if (octree.isNodeOccupied(*it))
290 std::cout <<
"Leaf node " << it.getX() <<
' ' << it.getY() <<
' ' << it.getZ() <<
'\n';
299 int numZ,
bool do_negs)
302 for (
unsigned int i = 0; i < points.size(); ++i)
305 df.
worldToGrid(points[i].x(), points[i].y(), points[i].z(), loc.x(), loc.y(), loc.z());
309 for (
int x = 0; x < numX; ++x)
311 for (
int y = 0; y < numY; ++y)
313 for (
int z = 0; z < numZ; ++z)
320 for (Eigen::Vector3i& point : points_ind)
322 if (point.x() == x && point.y() == y && point.z() == z)
330 ASSERT_GT(ndsq, 0) <<
"Obstacle point " << x <<
' ' << y <<
' ' << z <<
" has zero negative value";
332 ASSERT_TRUE(found) <<
"Obstacle point " << x <<
' ' << y <<
' ' << z <<
" not found";
339 TEST(TestPropagationDistanceField, TestAddRemovePoints)
348 EXPECT_EQ(num_x,
static_cast<int>(WIDTH / RESOLUTION + 0.5));
349 EXPECT_EQ(num_y,
static_cast<int>(HEIGHT / RESOLUTION + 0.5));
350 EXPECT_EQ(num_z,
static_cast<int>(DEPTH / RESOLUTION + 0.5));
353 double tgx, tgy, tgz;
355 EXPECT_NEAR(df.
getDistance(1000.0, 1000.0, 1000.0), MAX_DIST, .0001);
356 EXPECT_NEAR(df.
getDistanceGradient(1000.0, 1000.0, 1000.0, tgx, tgy, tgz, in_bounds), MAX_DIST, .0001);
357 EXPECT_FALSE(in_bounds);
360 EigenSTL::vector_Vector3d points;
361 points.push_back(POINT1);
362 points.push_back(POINT2);
369 points.push_back(POINT2);
370 points.push_back(POINT3);
371 EigenSTL::vector_Vector3d old_points;
372 old_points.push_back(POINT1);
381 points.push_back(POINT2);
384 points.push_back(POINT3);
390 points.push_back(POINT1);
404 double dist_grad = df.
getDistanceGradient(wx, wy, wz, grad.x(), grad.y(), grad.z(), grad_in_bounds);
405 ASSERT_TRUE(grad_in_bounds) << x <<
' ' << y <<
' ' << z;
406 ASSERT_NEAR(dist, dist_grad, .0001);
407 if (dist > 0 && dist < MAX_DIST)
409 double xscale = grad.x() / grad.norm();
410 double yscale = grad.y() / grad.norm();
411 double zscale = grad.z() / grad.norm();
413 double comp_x = wx - xscale * dist;
414 double comp_y = wy - yscale * dist;
415 double comp_z = wz - zscale * dist;
419 std::cout <<
"Dist " << dist <<
'\n';
420 std::cout <<
"Cell " << x <<
' ' << y <<
' ' << z <<
' ' << wx <<
' ' << wy <<
' ' << wz <<
'\n';
421 std::cout <<
"Scale " << xscale <<
' ' << yscale <<
' ' << zscale <<
'\n';
422 std::cout <<
"Grad " << grad.x() <<
' ' << grad.y() <<
' ' << grad.z() <<
" comp " << comp_x <<
' '
423 << comp_y <<
' ' << comp_z <<
'\n';
425 ASSERT_NEAR(comp_x, POINT1.x(), RESOLUTION)
426 << dist << x <<
' ' << y <<
' ' << z <<
' ' << grad.x() <<
' ' << grad.y() <<
' ' << grad.z() <<
' '
427 << xscale <<
' ' << yscale <<
' ' << zscale <<
'\n';
428 ASSERT_NEAR(comp_y, POINT1.y(), RESOLUTION)
429 << x <<
' ' << y <<
' ' << z <<
' ' << grad.x() <<
' ' << grad.y() <<
' ' << grad.z() <<
' ' << xscale
430 <<
' ' << yscale <<
' ' << zscale <<
'\n';
431 ASSERT_NEAR(comp_z, POINT1.z(), RESOLUTION)
432 << x <<
' ' << y <<
' ' << z <<
' ' << grad.x() <<
' ' << grad.y() <<
' ' << grad.z() <<
' ' << xscale
433 <<
' ' << yscale <<
' ' << zscale <<
'\n';
441 TEST(TestSignedPropagationDistanceField, TestSignedAddRemovePoints)
450 EXPECT_EQ(num_x,
static_cast<int>(WIDTH / RESOLUTION + 0.5));
451 EXPECT_EQ(num_y,
static_cast<int>(HEIGHT / RESOLUTION + 0.5));
452 EXPECT_EQ(num_z,
static_cast<int>(DEPTH / RESOLUTION + 0.5));
461 double lwx, lwy, lwz;
462 double hwx, hwy, hwz;
466 EigenSTL::vector_Vector3d points;
467 for (
double x = lwx; x <= hwx; x += .1)
469 for (
double y = lwy; y <= hwy; y += .1)
471 for (
double z = lwz; z <= hwz; z += .1)
489 EigenSTL::vector_Vector3d rem_points;
490 rem_points.push_back(center_point);
499 EigenSTL::vector_Vector3d test_points;
502 if (point.x() != center_point.x() || point.y() != center_point.y() || point.z() != center_point.z())
504 test_points.push_back(point);
510 PropagationDistanceField gradient_df(WIDTH, HEIGHT, DEPTH, RESOLUTION, ORIGIN_X, ORIGIN_Y, ORIGIN_Z, MAX_DIST,
true);
512 shapes::Sphere sphere(.25);
514 geometry_msgs::msg::Pose p;
515 p.orientation.w = 1.0;
520 Eigen::Isometry3d p_eigen;
521 tf2::fromMsg(p, p_eigen);
535 Eigen::Vector3i ncell_pos;
538 EXPECT_EQ(ncell_dist, dist);
540 if (ncell ==
nullptr)
545 <<
"dist=" << dist <<
" xyz=" << x <<
' ' << y <<
' ' << z <<
" ncell=" << ncell_pos.x() <<
' '
546 << ncell_pos.y() <<
' ' << ncell_pos.z() <<
'\n';
548 else if (ncell_dist < 0)
551 <<
"dist=" << dist <<
" xyz=" << x <<
' ' << y <<
' ' << z <<
" ncell=" << ncell_pos.x() <<
' '
552 << ncell_pos.y() <<
' ' << ncell_pos.z() <<
'\n';
564 double dist_grad = gradient_df.
getDistanceGradient(wx, wy, wz, grad.x(), grad.y(), grad.z(), grad_in_bounds);
565 ASSERT_TRUE(grad_in_bounds) << x <<
' ' << y <<
' ' << z;
566 ASSERT_NEAR(dist, dist_grad, .0001);
572 <<
"dist=" << dist <<
" xyz=" << x <<
' ' << y <<
' ' << z <<
" grad=" << grad.x() <<
' ' << grad.y()
573 <<
' ' << grad.z() <<
" ncell=" << ncell_pos.x() <<
' ' << ncell_pos.y() <<
' ' << ncell_pos.z() <<
'\n';
575 double grad_size_sq = grad.squaredNorm();
576 if (grad_size_sq < std::numeric_limits<double>::epsilon())
579 double oo_grad_size = 1.0 / sqrt(grad_size_sq);
580 double xscale = grad.x() * oo_grad_size;
581 double yscale = grad.y() * oo_grad_size;
582 double zscale = grad.z() * oo_grad_size;
584 double comp_x = wx - xscale * dist;
585 double comp_y = wy - yscale * dist;
586 double comp_z = wz - zscale * dist;
588 int cell_x, cell_y, cell_z;
589 bool cell_in_bounds = gradient_df.
worldToGrid(comp_x, comp_y, comp_z, cell_x, cell_y, cell_z);
591 ASSERT_EQ(cell_in_bounds,
true);
595 EXPECT_EQ(ncell_pos.x(), cell_x);
596 EXPECT_EQ(ncell_pos.y(), cell_y);
597 EXPECT_EQ(ncell_pos.z(), cell_z);
598 EXPECT_EQ(ncell, cell);
601 << dist <<
' ' << x <<
' ' << y <<
' ' << z <<
' ' << grad.x() <<
' ' << grad.y() <<
' ' << grad.z()
602 <<
' ' << xscale <<
' ' << yscale <<
' ' << zscale <<
" cell " << comp_x <<
' ' << comp_y <<
' ' << comp_z
610 TEST(TestSignedPropagationDistanceField, TestShape)
618 shapes::Sphere sphere(.25);
620 Eigen::Isometry3d p = Eigen::Translation3d(0.5, 0.5, 0.5) * Eigen::Quaterniond(0.0, 0.0, 0.0, 1.0);
621 Eigen::Isometry3d np = Eigen::Translation3d(0.7, 0.7, 0.7) * Eigen::Quaterniond(0.0, 0.0, 0.0, 1.0);
625 bodies::Body* body = bodies::createBodyFromShape(&sphere);
627 EigenSTL::vector_Vector3d point_vec;
639 body = bodies::createBodyFromShape(&sphere);
642 EigenSTL::vector_Vector3d point_vec_2;
645 EigenSTL::vector_Vector3d point_vec_union = point_vec_2;
646 point_vec_union.insert(point_vec_union.end(), point_vec.begin(), point_vec.end());
660 static const double PERF_WIDTH = 3.0;
661 static const double PERF_HEIGHT = 3.0;
662 static const double PERF_DEPTH = 4.0;
663 static const double PERF_RESOLUTION = 0.02;
664 static const double PERF_ORIGIN_X = 0.0;
665 static const double PERF_ORIGIN_Y = 0.0;
666 static const double PERF_ORIGIN_Z = 0.0;
667 static const double PERF_MAX_DIST = .25;
668 static const unsigned int UNIFORM_DISTANCE = 10;
670 TEST(TestSignedPropagationDistanceField, TestPerformance)
672 std::cout <<
"Creating distance field with "
673 << (PERF_WIDTH / PERF_RESOLUTION) * (PERF_HEIGHT / PERF_RESOLUTION) * (PERF_DEPTH / PERF_RESOLUTION)
674 <<
" entries" <<
'\n';
676 auto dt = std::chrono::system_clock::now();
678 PERF_ORIGIN_Z, PERF_MAX_DIST,
false);
680 <<
"Creating unsigned took "
681 << std::chrono::duration_cast<std::chrono::milliseconds>(std::chrono::system_clock::now() - dt).count() / 1000.0
684 dt = std::chrono::system_clock::now();
686 PERF_ORIGIN_Z, PERF_MAX_DIST,
true);
689 <<
"Creating signed took "
690 << std::chrono::duration_cast<std::chrono::milliseconds>(std::chrono::system_clock::now() - dt).count() / 1000.0
693 shapes::Box big_table(2.0, 2.0, .5);
695 Eigen::Isometry3d p = Eigen::Translation3d(PERF_WIDTH / 2.0, PERF_DEPTH / 2.0, PERF_HEIGHT / 2.0) *
696 Eigen::Quaterniond(0.0, 0.0, 0.0, 1.0);
697 Eigen::Isometry3d np = Eigen::Translation3d(PERF_WIDTH / 2.0 + .01, PERF_DEPTH / 2.0, PERF_HEIGHT / 2.0) *
698 Eigen::Quaterniond(0.0, 0.0, 0.0, 1.0);
700 unsigned int big_num_points = ceil(2.0 / PERF_RESOLUTION) * ceil(2.0 / PERF_RESOLUTION) * ceil(.5 / PERF_RESOLUTION);
702 std::cout <<
"Adding " << big_num_points <<
" points" <<
'\n';
704 dt = std::chrono::system_clock::now();
707 <<
"Adding to unsigned took "
708 << std::chrono::duration_cast<std::chrono::milliseconds>(std::chrono::system_clock::now() - dt).count() / 1000.0
711 << (std::chrono::duration_cast<std::chrono::milliseconds>(std::chrono::system_clock::now() - dt).count() /
713 (big_num_points * 1.0)
716 dt = std::chrono::system_clock::now();
719 <<
"Re-adding to unsigned took "
720 << std::chrono::duration_cast<std::chrono::milliseconds>(std::chrono::system_clock::now() - dt).count() / 1000.0
723 dt = std::chrono::system_clock::now();
726 <<
"Adding to signed took "
727 << std::chrono::duration_cast<std::chrono::milliseconds>(std::chrono::system_clock::now() - dt).count() / 1000.0
730 << (std::chrono::duration_cast<std::chrono::milliseconds>(std::chrono::system_clock::now() - dt).count() /
732 (big_num_points * 1.0)
735 dt = std::chrono::system_clock::now();
738 <<
"Moving in unsigned took "
739 << std::chrono::duration_cast<std::chrono::milliseconds>(std::chrono::system_clock::now() - dt).count() / 1000.0
742 dt = std::chrono::system_clock::now();
745 <<
"Moving in signed took "
746 << std::chrono::duration_cast<std::chrono::milliseconds>(std::chrono::system_clock::now() - dt).count() / 1000.0
749 dt = std::chrono::system_clock::now();
752 <<
"Removing from unsigned took "
753 << std::chrono::duration_cast<std::chrono::milliseconds>(std::chrono::system_clock::now() - dt).count() / 1000.0
756 dt = std::chrono::system_clock::now();
759 <<
"Removing from signed took "
760 << std::chrono::duration_cast<std::chrono::milliseconds>(std::chrono::system_clock::now() - dt).count() / 1000.0
763 dt = std::chrono::system_clock::now();
766 shapes::Box small_table(.25, .25, .05);
768 unsigned int small_num_points = (13) * (13) * (3);
770 std::cout <<
"Adding " << small_num_points <<
" points" <<
'\n';
772 dt = std::chrono::system_clock::now();
775 <<
"Adding to unsigned took "
776 << std::chrono::duration_cast<std::chrono::milliseconds>(std::chrono::system_clock::now() - dt).count() / 1000.0
778 <<
" avg " << (std::chrono::system_clock::now() - dt).count() / (small_num_points * 1.0) <<
'\n';
780 dt = std::chrono::system_clock::now();
783 <<
"Adding to signed took "
784 << std::chrono::duration_cast<std::chrono::milliseconds>(std::chrono::system_clock::now() - dt).count() / 1000.0
786 <<
" avg " << (std::chrono::system_clock::now() - dt).count() / (small_num_points * 1.0) <<
'\n';
788 dt = std::chrono::system_clock::now();
791 <<
"Moving in unsigned took "
792 << std::chrono::duration_cast<std::chrono::milliseconds>(std::chrono::system_clock::now() - dt).count() / 1000.0
795 dt = std::chrono::system_clock::now();
798 <<
"Moving in signed took "
799 << std::chrono::duration_cast<std::chrono::milliseconds>(std::chrono::system_clock::now() - dt).count() / 1000.0
803 PropagationDistanceField worstdfu(PERF_WIDTH, PERF_HEIGHT, PERF_DEPTH, PERF_RESOLUTION, PERF_ORIGIN_X, PERF_ORIGIN_Y,
804 PERF_ORIGIN_Z, PERF_MAX_DIST,
false);
806 PropagationDistanceField worstdfs(PERF_WIDTH, PERF_HEIGHT, PERF_DEPTH, PERF_RESOLUTION, PERF_ORIGIN_X, PERF_ORIGIN_Y,
807 PERF_ORIGIN_Z, PERF_MAX_DIST,
true);
809 EigenSTL::vector_Vector3d bad_vec;
810 for (
unsigned int z = UNIFORM_DISTANCE; z < worstdfu.
getZNumCells() - UNIFORM_DISTANCE; z += UNIFORM_DISTANCE)
812 for (
unsigned int x = UNIFORM_DISTANCE; x < worstdfu.
getXNumCells() - UNIFORM_DISTANCE; x += UNIFORM_DISTANCE)
814 for (
unsigned int y = UNIFORM_DISTANCE; y < worstdfu.
getYNumCells() - UNIFORM_DISTANCE; y += UNIFORM_DISTANCE)
817 bool valid = worstdfu.
gridToWorld(x, y, z, loc.x(), loc.y(), loc.z());
823 bad_vec.push_back(loc);
828 dt = std::chrono::system_clock::now();
830 std::chrono::duration<double> wd = std::chrono::system_clock::now() - dt;
831 printf(
"Time for unsigned adding %u uniform points is %g average %g\n",
static_cast<unsigned int>(bad_vec.size()),
832 wd.count(), wd.count() / (bad_vec.size() * 1.0));
833 dt = std::chrono::system_clock::now();
835 wd = std::chrono::system_clock::now() - dt;
836 printf(
"Time for signed adding %u uniform points is %g average %g\n",
static_cast<unsigned int>(bad_vec.size()),
837 wd.count(), wd.count() / (bad_vec.size() * 1.0));
840 TEST(TestSignedPropagationDistanceField, TestOcTree)
843 PERF_ORIGIN_Z, PERF_MAX_DIST,
false);
845 octomap::OcTree tree(.02);
847 unsigned int count = 0;
848 for (
float x = 1.01; x < 1.5; x += .02)
850 for (
float y = 1.01; y < 1.5; y += .02)
852 for (
float z = 1.01; z < 1.5; z += .02, ++count)
854 octomap::point3d point(x, y, z);
855 tree.updateNode(point,
true);
861 for (
float x = 2.51; x < 3.5; x += .02)
863 for (
float y = 1.01; y < 3.5; y += .02)
865 for (
float z = 1.01; z < 3.5; z += .02, ++count)
867 octomap::point3d point(x, y, z);
868 tree.updateNode(point,
true);
873 std::cout <<
"OcTree nodes " << count <<
'\n';
879 for (
float x = .01; x < .50; x += .02)
881 for (
float y = .01; y < .50; y += .02)
883 for (
float z = .01; z < .50; z += .02, ++count)
885 octomap::point3d point(x, y, z);
886 tree.updateNode(point,
true);
893 PropagationDistanceField df_oct(tree, octomap::point3d(0.5, 0.5, 0.5), octomap::point3d(5.0, 5.0, 5.0), PERF_MAX_DIST,
899 octomap::OcTree tree_lowres(.05);
900 octomap::point3d point1(.5, .5, .5);
901 octomap::point3d point2(.7, .5, .5);
902 octomap::point3d point3(1.0, .5, .5);
903 tree_lowres.updateNode(point1,
true);
904 tree_lowres.updateNode(point2,
true);
905 tree_lowres.updateNode(point3,
true);
909 PERF_ORIGIN_Y, PERF_ORIGIN_Z, PERF_MAX_DIST,
false);
916 auto tree_shape = std::make_shared<octomap::OcTree>(.05);
917 octomap::point3d tpoint1(1.0, .5, 1.0);
918 octomap::point3d tpoint2(1.7, .5, .5);
919 octomap::point3d tpoint3(1.8, .5, .5);
920 tree_shape->updateNode(tpoint1,
true);
921 tree_shape->updateNode(tpoint2,
true);
922 tree_shape->updateNode(tpoint3,
true);
924 auto shape_oc = std::make_shared<shapes::OcTree>(tree_shape);
927 PERF_ORIGIN_Y, PERF_ORIGIN_Z, PERF_MAX_DIST,
false);
930 PERF_ORIGIN_Y, PERF_ORIGIN_Z, PERF_MAX_DIST,
false);
937 TEST(TestSignedPropagationDistanceField, TestReadWrite)
941 EigenSTL::vector_Vector3d points;
942 points.push_back(POINT1);
943 points.push_back(POINT2);
944 points.push_back(POINT3);
947 std::ofstream sf(
"test_small.df", std::ios::out);
953 std::ifstream si(
"test_small.df", std::ios::in | std::ios::binary);
958 PERF_ORIGIN_Z, PERF_MAX_DIST,
false);
960 shapes::Sphere sphere(.5);
962 Eigen::Isometry3d p = Eigen::Translation3d(0.5, 0.5, 0.5) * Eigen::Quaterniond(0.0, 0.0, 0.0, 1.0);
966 std::ofstream
f(
"test_big.df", std::ios::out);
971 std::ifstream i(
"test_big.df", std::ios::in);
978 std::ifstream i2(
"test_big.df", std::ios::in);
979 auto wt = std::chrono::system_clock::now();
981 std::cout <<
"Reconstruction for big file took " << (std::chrono::system_clock::now() - wt).count() <<
'\n';
985 int main(
int argc,
char** argv)
987 testing::InitGoogleTest(&argc, argv);
988 return RUN_ALL_TESTS();
void moveShapeInField(const shapes::Shape *shape, const Eigen::Isometry3d &old_pose, const Eigen::Isometry3d &new_pose)
Moves the shape in the distance field from the old pose to the new pose, removing points that are no ...
void removeShapeFromField(const shapes::Shape *shape, const Eigen::Isometry3d &pose)
All points corresponding to the shape are removed from the distance field.
double getDistanceGradient(double x, double y, double z, double &gradient_x, double &gradient_y, double &gradient_z, bool &in_bounds) const
Gets not only the distance to the nearest cell but the gradient direction. The gradient is computed a...
void addOcTreeToField(const octomap::OcTree *octree)
Adds an octree to the distance field. Cells that are occupied in the octree that lie within the voxel...
double getResolution() const
Gets the resolution of the distance field in meters.
void addShapeToField(const shapes::Shape *shape, const Eigen::Isometry3d &pose)
Adds the set of points corresponding to the shape at the given pose as obstacle points into the dista...
A DistanceField implementation that uses a vector propagation method. Distances propagate outward fro...
void addPointsToField(const EigenSTL::vector_Vector3d &points) override
Add a set of obstacle points to the distance field, updating distance values accordingly....
void reset() override
Resets the entire distance field to max_distance for positive values and zero for negative values.
int getXNumCells() const override
Gets the number of cells along the X axis.
int getZNumCells() const override
Gets the number of cells along the Z axis.
bool worldToGrid(double world_x, double world_y, double world_z, int &x, int &y, int &z) const override
Converts from a world location to a set of integer indices. Should return false if the world location...
void removePointsFromField(const EigenSTL::vector_Vector3d &points) override
Remove a set of obstacle points from the distance field, updating distance values accordingly.
double getUninitializedDistance() const override
Gets a distance value for an invalid cell.
double getDistance(double x, double y, double z) const override
Get the distance value associated with the cell indicated by the world coordinate....
int getYNumCells() const override
Gets the number of cells along the Y axis.
const PropDistanceFieldVoxel & getCell(int x, int y, int z) const
Gets full cell data given an index.
void updatePointsInField(const EigenSTL::vector_Vector3d &old_points, const EigenSTL::vector_Vector3d &new_points) override
This function will remove any obstacle points that are in the old point set but not the new point set...
bool writeToStream(std::ostream &stream) const override
Writes the contents of the distance field to the supplied stream.
const PropDistanceFieldVoxel * getNearestCell(int x, int y, int z, double &dist, Eigen::Vector3i &pos) const
Gets nearest surface cell and returns distance to it.
bool gridToWorld(int x, int y, int z, double &world_x, double &world_y, double &world_z) const override
Converts from an set of integer indices to a world location given the origin and resolution parameter...
std::vector< Eigen::Vector3i, Eigen::aligned_allocator< Eigen::Vector3i > > vector_Vector3i
Namespace for holding classes that generate distance fields.
void findInternalPointsConvex(const bodies::Body &body, double resolution, EigenSTL::vector_Vector3d &points)
Find all points on a regular grid that are internal to the body, assuming the body is a convex shape....
Vec3fX< details::Vec3Data< double > > Vector3d
Structure that holds voxel information for the DistanceField. Will be used in VoxelGrid.
Eigen::Vector3i closest_point_
Closest occupied cell.
Eigen::Vector3i closest_negative_point_
Closest unoccupied cell.
int negative_distance_square_
Distance in cells to the nearest unoccupied cell, squared.
int distance_square_
Distance in cells to the closest obstacle, squared.
unsigned int countLeafNodes(const octomap::OcTree &octree)
void print(PropagationDistanceField &pdf, int numX, int numY, int numZ)
int main(int argc, char **argv)
void printPointCoords(const Eigen::Vector3i &p)
bool areDistanceFieldsDistancesEqual(const PropagationDistanceField &df1, const PropagationDistanceField &df2)
void printBoth(PropagationDistanceField &pdf, int numX, int numY, int numZ)
void checkDistanceField(const PropagationDistanceField &df, const EigenSTL::vector_Vector3d &points, int numX, int numY, int numZ, bool do_negs)
bool checkOctomapVersusDistanceField(const PropagationDistanceField &df, const octomap::OcTree &octree)
void printNeg(PropagationDistanceField &pdf, int numX, int numY, int numZ)
int distanceSequence(int x, int y, int z)
TEST(TestPropagationDistanceField, TestAddRemovePoints)
unsigned int countOccupiedCells(const PropagationDistanceField &df)