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)
134 std::cout <<
"Positive distance square ... negative distance square\n";
135 for (
int z = 0;
z < numZ; ++
z)
137 std::cout <<
"Z=" <<
z <<
'\n';
138 for (
int y = 0;
y < numY; ++
y)
140 for (
int x = 0;
x < numX; ++
x)
145 for (
int x = 0;
x < numX; ++
x)
150 for (
int x = 0;
x < numX; ++
x)
155 for (
int x = 0;
x < numX; ++
x)
187 printf(
"Cell %d %d %d neg distances not equal %d %d\n",
x,
y,
z,
211 octomap::point3d query(qx, qy, qz);
212 octomap::OcTreeNode* result = octree.search(query);
224 octomap::point3d query_boundary(boundary_x, boundary_y, boundary_z);
225 result = octree.search(query_boundary);
235 std::cout <<
"No point at potential boundary query " << query.x() <<
" " << query.y() <<
" " << query.z()
240 if (!octree.isNodeOccupied(result))
242 std::cout <<
"Disagreement at " << qx <<
" " << qy <<
" " << qz <<
'\n';
254 unsigned int count = 0;
273 unsigned int count = 0;
274 for (octomap::OcTree::leaf_iterator it = octree.begin_leafs(), end = octree.end_leafs(); it != end; ++it)
276 if (octree.isNodeOccupied(*it))
278 std::cout <<
"Leaf node " << it.getX() <<
" " << it.getY() <<
" " << it.getZ() <<
'\n';
287 int numY,
int numZ,
bool do_negs)
290 for (
unsigned int i = 0; i < points.size(); ++i)
293 df.
worldToGrid(points[i].
x(), points[i].
y(), points[i].
z(), loc.x(), loc.y(), loc.z());
297 for (
int x = 0;
x < numX; ++
x)
299 for (
int y = 0;
y < numY; ++
y)
301 for (
int z = 0;
z < numZ; ++
z)
308 for (Eigen::Vector3i& point : points_ind)
310 if (point.x() ==
x && point.y() ==
y && point.z() ==
z)
318 ASSERT_GT(ndsq, 0) <<
"Obstacle point " <<
x <<
" " <<
y <<
" " <<
z <<
" has zero negative value";
320 ASSERT_TRUE(found) <<
"Obstacle point " <<
x <<
" " <<
y <<
" " <<
z <<
" not found";
327 TEST(TestPropagationDistanceField, TestAddRemovePoints)
336 EXPECT_EQ(num_x,
static_cast<int>(WIDTH / RESOLUTION + 0.5));
337 EXPECT_EQ(num_y,
static_cast<int>(HEIGHT / RESOLUTION + 0.5));
338 EXPECT_EQ(num_z,
static_cast<int>(DEPTH / RESOLUTION + 0.5));
341 double tgx, tgy, tgz;
343 EXPECT_NEAR(df.
getDistance(1000.0, 1000.0, 1000.0), MAX_DIST, .0001);
344 EXPECT_NEAR(df.
getDistanceGradient(1000.0, 1000.0, 1000.0, tgx, tgy, tgz, in_bounds), MAX_DIST, .0001);
345 EXPECT_FALSE(in_bounds);
348 EigenSTL::vector_Vector3d points;
349 points.push_back(POINT1);
350 points.push_back(POINT2);
357 points.push_back(POINT2);
358 points.push_back(POINT3);
359 EigenSTL::vector_Vector3d old_points;
360 old_points.push_back(POINT1);
369 points.push_back(POINT2);
372 points.push_back(POINT3);
378 points.push_back(POINT1);
392 double dist_grad = df.
getDistanceGradient(wx, wy, wz, grad.x(), grad.y(), grad.z(), grad_in_bounds);
393 ASSERT_TRUE(grad_in_bounds) <<
x <<
" " <<
y <<
" " <<
z;
394 ASSERT_NEAR(dist, dist_grad, .0001);
395 if (dist > 0 && dist < MAX_DIST)
397 double xscale = grad.x() / grad.norm();
398 double yscale = grad.y() / grad.norm();
399 double zscale = grad.z() / grad.norm();
401 double comp_x = wx - xscale * dist;
402 double comp_y = wy - yscale * dist;
403 double comp_z = wz - zscale * dist;
407 std::cout <<
"Dist " << dist <<
'\n';
408 std::cout <<
"Cell " <<
x <<
" " <<
y <<
" " <<
z <<
" " << wx <<
" " << wy <<
" " << wz <<
'\n';
409 std::cout <<
"Scale " << xscale <<
" " << yscale <<
" " << zscale <<
'\n';
410 std::cout <<
"Grad " << grad.x() <<
" " << grad.y() <<
" " << grad.z() <<
" comp " << comp_x <<
" "
411 << comp_y <<
" " << comp_z <<
'\n';
413 ASSERT_NEAR(comp_x, POINT1.x(), RESOLUTION)
414 << dist <<
x <<
" " <<
y <<
" " <<
z <<
" " << grad.x() <<
" " << grad.y() <<
" " << grad.z() <<
" "
415 << xscale <<
" " << yscale <<
" " << zscale <<
'\n';
416 ASSERT_NEAR(comp_y, POINT1.y(), RESOLUTION)
417 <<
x <<
" " <<
y <<
" " <<
z <<
" " << grad.x() <<
" " << grad.y() <<
" " << grad.z() <<
" " << xscale
418 <<
" " << yscale <<
" " << zscale <<
'\n';
419 ASSERT_NEAR(comp_z, POINT1.z(), RESOLUTION)
420 <<
x <<
" " <<
y <<
" " <<
z <<
" " << grad.x() <<
" " << grad.y() <<
" " << grad.z() <<
" " << xscale
421 <<
" " << yscale <<
" " << zscale <<
'\n';
429 TEST(TestSignedPropagationDistanceField, TestSignedAddRemovePoints)
438 EXPECT_EQ(num_x,
static_cast<int>(WIDTH / RESOLUTION + 0.5));
439 EXPECT_EQ(num_y,
static_cast<int>(HEIGHT / RESOLUTION + 0.5));
440 EXPECT_EQ(num_z,
static_cast<int>(DEPTH / RESOLUTION + 0.5));
449 double lwx, lwy, lwz;
450 double hwx, hwy, hwz;
454 EigenSTL::vector_Vector3d points;
455 for (
double x = lwx;
x <= hwx;
x += .1)
457 for (
double y = lwy;
y <= hwy;
y += .1)
459 for (
double z = lwz;
z <= hwz;
z += .1)
477 EigenSTL::vector_Vector3d rem_points;
478 rem_points.push_back(center_point);
487 EigenSTL::vector_Vector3d test_points;
490 if (point.x() != center_point.x() || point.y() != center_point.y() || point.z() != center_point.z())
492 test_points.push_back(point);
498 PropagationDistanceField gradient_df(WIDTH, HEIGHT, DEPTH, RESOLUTION, ORIGIN_X, ORIGIN_Y, ORIGIN_Z, MAX_DIST,
true);
500 shapes::Sphere sphere(.25);
502 geometry_msgs::msg::Pose
p;
503 p.orientation.w = 1.0;
508 Eigen::Isometry3d p_eigen;
509 tf2::fromMsg(
p, p_eigen);
523 Eigen::Vector3i ncell_pos;
526 EXPECT_EQ(ncell_dist, dist);
528 if (ncell ==
nullptr)
533 <<
"dist=" << dist <<
" xyz=" <<
x <<
" " <<
y <<
" " <<
z <<
" ncell=" << ncell_pos.x() <<
" "
534 << ncell_pos.y() <<
" " << ncell_pos.z() <<
'\n';
536 else if (ncell_dist < 0)
539 <<
"dist=" << dist <<
" xyz=" <<
x <<
" " <<
y <<
" " <<
z <<
" ncell=" << ncell_pos.x() <<
" "
540 << ncell_pos.y() <<
" " << ncell_pos.z() <<
'\n';
552 double dist_grad = gradient_df.
getDistanceGradient(wx, wy, wz, grad.x(), grad.y(), grad.z(), grad_in_bounds);
553 ASSERT_TRUE(grad_in_bounds) <<
x <<
" " <<
y <<
" " <<
z;
554 ASSERT_NEAR(dist, dist_grad, .0001);
560 <<
"dist=" << dist <<
" xyz=" <<
x <<
" " <<
y <<
" " <<
z <<
" grad=" << grad.x() <<
" " << grad.y()
561 <<
" " << grad.z() <<
" ncell=" << ncell_pos.x() <<
" " << ncell_pos.y() <<
" " << ncell_pos.z() <<
'\n';
563 double grad_size_sq = grad.squaredNorm();
564 if (grad_size_sq < std::numeric_limits<double>::epsilon())
567 double oo_grad_size = 1.0 / sqrt(grad_size_sq);
568 double xscale = grad.x() * oo_grad_size;
569 double yscale = grad.y() * oo_grad_size;
570 double zscale = grad.z() * oo_grad_size;
572 double comp_x = wx - xscale * dist;
573 double comp_y = wy - yscale * dist;
574 double comp_z = wz - zscale * dist;
576 int cell_x, cell_y, cell_z;
577 bool cell_in_bounds = gradient_df.
worldToGrid(comp_x, comp_y, comp_z, cell_x, cell_y, cell_z);
579 ASSERT_EQ(cell_in_bounds,
true);
583 EXPECT_EQ(ncell_pos.x(), cell_x);
584 EXPECT_EQ(ncell_pos.y(), cell_y);
585 EXPECT_EQ(ncell_pos.z(), cell_z);
586 EXPECT_EQ(ncell, cell);
589 << dist <<
" " <<
x <<
" " <<
y <<
" " <<
z <<
" " << grad.x() <<
" " << grad.y() <<
" " << grad.z()
590 <<
" " << xscale <<
" " << yscale <<
" " << zscale <<
" cell " << comp_x <<
" " << comp_y <<
" " << comp_z
598 TEST(TestSignedPropagationDistanceField, TestShape)
606 shapes::Sphere sphere(.25);
608 Eigen::Isometry3d
p = Eigen::Translation3d(0.5, 0.5, 0.5) * Eigen::Quaterniond(0.0, 0.0, 0.0, 1.0);
609 Eigen::Isometry3d np = Eigen::Translation3d(0.7, 0.7, 0.7) * Eigen::Quaterniond(0.0, 0.0, 0.0, 1.0);
613 bodies::Body* body = bodies::createBodyFromShape(&sphere);
615 EigenSTL::vector_Vector3d point_vec;
627 body = bodies::createBodyFromShape(&sphere);
630 EigenSTL::vector_Vector3d point_vec_2;
633 EigenSTL::vector_Vector3d point_vec_union = point_vec_2;
634 point_vec_union.insert(point_vec_union.end(), point_vec.begin(), point_vec.end());
648 static const double PERF_WIDTH = 3.0;
649 static const double PERF_HEIGHT = 3.0;
650 static const double PERF_DEPTH = 4.0;
651 static const double PERF_RESOLUTION = 0.02;
652 static const double PERF_ORIGIN_X = 0.0;
653 static const double PERF_ORIGIN_Y = 0.0;
654 static const double PERF_ORIGIN_Z = 0.0;
655 static const double PERF_MAX_DIST = .25;
656 static const unsigned int UNIFORM_DISTANCE = 10;
658 TEST(TestSignedPropagationDistanceField, TestPerformance)
660 std::cout <<
"Creating distance field with "
661 << (PERF_WIDTH / PERF_RESOLUTION) * (PERF_HEIGHT / PERF_RESOLUTION) * (PERF_DEPTH / PERF_RESOLUTION)
662 <<
" entries" <<
'\n';
664 auto dt = std::chrono::system_clock::now();
666 PERF_ORIGIN_Z, PERF_MAX_DIST,
false);
668 <<
"Creating unsigned took "
669 << std::chrono::duration_cast<std::chrono::milliseconds>(std::chrono::system_clock::now() - dt).count() / 1000.0
672 dt = std::chrono::system_clock::now();
674 PERF_ORIGIN_Z, PERF_MAX_DIST,
true);
677 <<
"Creating signed took "
678 << std::chrono::duration_cast<std::chrono::milliseconds>(std::chrono::system_clock::now() - dt).count() / 1000.0
681 shapes::Box big_table(2.0, 2.0, .5);
683 Eigen::Isometry3d
p = Eigen::Translation3d(PERF_WIDTH / 2.0, PERF_DEPTH / 2.0, PERF_HEIGHT / 2.0) *
684 Eigen::Quaterniond(0.0, 0.0, 0.0, 1.0);
685 Eigen::Isometry3d np = Eigen::Translation3d(PERF_WIDTH / 2.0 + .01, PERF_DEPTH / 2.0, PERF_HEIGHT / 2.0) *
686 Eigen::Quaterniond(0.0, 0.0, 0.0, 1.0);
688 unsigned int big_num_points = ceil(2.0 / PERF_RESOLUTION) * ceil(2.0 / PERF_RESOLUTION) * ceil(.5 / PERF_RESOLUTION);
690 std::cout <<
"Adding " << big_num_points <<
" points" <<
'\n';
692 dt = std::chrono::system_clock::now();
695 <<
"Adding to unsigned took "
696 << std::chrono::duration_cast<std::chrono::milliseconds>(std::chrono::system_clock::now() - dt).count() / 1000.0
699 << (std::chrono::duration_cast<std::chrono::milliseconds>(std::chrono::system_clock::now() - dt).count() /
701 (big_num_points * 1.0)
704 dt = std::chrono::system_clock::now();
707 <<
"Re-adding to unsigned took "
708 << std::chrono::duration_cast<std::chrono::milliseconds>(std::chrono::system_clock::now() - dt).count() / 1000.0
711 dt = std::chrono::system_clock::now();
714 <<
"Adding to signed took "
715 << std::chrono::duration_cast<std::chrono::milliseconds>(std::chrono::system_clock::now() - dt).count() / 1000.0
718 << (std::chrono::duration_cast<std::chrono::milliseconds>(std::chrono::system_clock::now() - dt).count() /
720 (big_num_points * 1.0)
723 dt = std::chrono::system_clock::now();
726 <<
"Moving in unsigned took "
727 << std::chrono::duration_cast<std::chrono::milliseconds>(std::chrono::system_clock::now() - dt).count() / 1000.0
730 dt = std::chrono::system_clock::now();
733 <<
"Moving in signed took "
734 << std::chrono::duration_cast<std::chrono::milliseconds>(std::chrono::system_clock::now() - dt).count() / 1000.0
737 dt = std::chrono::system_clock::now();
740 <<
"Removing from unsigned took "
741 << std::chrono::duration_cast<std::chrono::milliseconds>(std::chrono::system_clock::now() - dt).count() / 1000.0
744 dt = std::chrono::system_clock::now();
747 <<
"Removing from signed took "
748 << std::chrono::duration_cast<std::chrono::milliseconds>(std::chrono::system_clock::now() - dt).count() / 1000.0
751 dt = std::chrono::system_clock::now();
754 shapes::Box small_table(.25, .25, .05);
756 unsigned int small_num_points = (13) * (13) * (3);
758 std::cout <<
"Adding " << small_num_points <<
" points" <<
'\n';
760 dt = std::chrono::system_clock::now();
763 <<
"Adding to unsigned took "
764 << std::chrono::duration_cast<std::chrono::milliseconds>(std::chrono::system_clock::now() - dt).count() / 1000.0
766 <<
" avg " << (std::chrono::system_clock::now() - dt).count() / (small_num_points * 1.0) <<
'\n';
768 dt = std::chrono::system_clock::now();
771 <<
"Adding to signed took "
772 << std::chrono::duration_cast<std::chrono::milliseconds>(std::chrono::system_clock::now() - dt).count() / 1000.0
774 <<
" avg " << (std::chrono::system_clock::now() - dt).count() / (small_num_points * 1.0) <<
'\n';
776 dt = std::chrono::system_clock::now();
779 <<
"Moving in unsigned took "
780 << std::chrono::duration_cast<std::chrono::milliseconds>(std::chrono::system_clock::now() - dt).count() / 1000.0
783 dt = std::chrono::system_clock::now();
786 <<
"Moving in signed took "
787 << std::chrono::duration_cast<std::chrono::milliseconds>(std::chrono::system_clock::now() - dt).count() / 1000.0
791 PropagationDistanceField worstdfu(PERF_WIDTH, PERF_HEIGHT, PERF_DEPTH, PERF_RESOLUTION, PERF_ORIGIN_X, PERF_ORIGIN_Y,
792 PERF_ORIGIN_Z, PERF_MAX_DIST,
false);
794 PropagationDistanceField worstdfs(PERF_WIDTH, PERF_HEIGHT, PERF_DEPTH, PERF_RESOLUTION, PERF_ORIGIN_X, PERF_ORIGIN_Y,
795 PERF_ORIGIN_Z, PERF_MAX_DIST,
true);
797 EigenSTL::vector_Vector3d bad_vec;
798 unsigned int count = 0;
799 for (
unsigned int z = UNIFORM_DISTANCE;
z < worstdfu.
getZNumCells() - UNIFORM_DISTANCE;
z += UNIFORM_DISTANCE)
801 for (
unsigned int x = UNIFORM_DISTANCE;
x < worstdfu.
getXNumCells() - UNIFORM_DISTANCE;
x += UNIFORM_DISTANCE)
803 for (
unsigned int y = UNIFORM_DISTANCE;
y < worstdfu.
getYNumCells() - UNIFORM_DISTANCE;
y += UNIFORM_DISTANCE)
807 bool valid = worstdfu.
gridToWorld(
x,
y,
z, loc.x(), loc.y(), loc.z());
814 bad_vec.push_back(loc);
819 dt = std::chrono::system_clock::now();
821 std::chrono::duration<double> wd = std::chrono::system_clock::now() - dt;
822 printf(
"Time for unsigned adding %u uniform points is %g average %g\n", (
unsigned int)bad_vec.size(), wd.count(),
823 wd.count() / (bad_vec.size() * 1.0));
824 dt = std::chrono::system_clock::now();
826 wd = std::chrono::system_clock::now() - dt;
827 printf(
"Time for signed adding %u uniform points is %g average %g\n", (
unsigned int)bad_vec.size(), wd.count(),
828 wd.count() / (bad_vec.size() * 1.0));
831 TEST(TestSignedPropagationDistanceField, TestOcTree)
834 PERF_ORIGIN_Z, PERF_MAX_DIST,
false);
836 octomap::OcTree tree(.02);
838 unsigned int count = 0;
839 for (
float x = 1.01;
x < 1.5;
x += .02)
841 for (
float y = 1.01;
y < 1.5;
y += .02)
843 for (
float z = 1.01;
z < 1.5;
z += .02, ++count)
845 octomap::point3d point(
x,
y,
z);
846 tree.updateNode(point,
true);
852 for (
float x = 2.51;
x < 3.5;
x += .02)
854 for (
float y = 1.01;
y < 3.5;
y += .02)
856 for (
float z = 1.01;
z < 3.5;
z += .02, ++count)
858 octomap::point3d point(
x,
y,
z);
859 tree.updateNode(point,
true);
864 std::cout <<
"OcTree nodes " << count <<
'\n';
870 for (
float x = .01;
x < .50;
x += .02)
872 for (
float y = .01;
y < .50;
y += .02)
874 for (
float z = .01;
z < .50;
z += .02, ++count)
876 octomap::point3d point(
x,
y,
z);
877 tree.updateNode(point,
true);
884 PropagationDistanceField df_oct(tree, octomap::point3d(0.5, 0.5, 0.5), octomap::point3d(5.0, 5.0, 5.0), PERF_MAX_DIST,
890 octomap::OcTree tree_lowres(.05);
891 octomap::point3d point1(.5, .5, .5);
892 octomap::point3d point2(.7, .5, .5);
893 octomap::point3d point3(1.0, .5, .5);
894 tree_lowres.updateNode(point1,
true);
895 tree_lowres.updateNode(point2,
true);
896 tree_lowres.updateNode(point3,
true);
900 PERF_ORIGIN_Y, PERF_ORIGIN_Z, PERF_MAX_DIST,
false);
907 auto tree_shape = std::make_shared<octomap::OcTree>(.05);
908 octomap::point3d tpoint1(1.0, .5, 1.0);
909 octomap::point3d tpoint2(1.7, .5, .5);
910 octomap::point3d tpoint3(1.8, .5, .5);
911 tree_shape->updateNode(tpoint1,
true);
912 tree_shape->updateNode(tpoint2,
true);
913 tree_shape->updateNode(tpoint3,
true);
915 auto shape_oc = std::make_shared<shapes::OcTree>(tree_shape);
918 PERF_ORIGIN_Y, PERF_ORIGIN_Z, PERF_MAX_DIST,
false);
921 PERF_ORIGIN_Y, PERF_ORIGIN_Z, PERF_MAX_DIST,
false);
928 TEST(TestSignedPropagationDistanceField, TestReadWrite)
932 EigenSTL::vector_Vector3d points;
933 points.push_back(POINT1);
934 points.push_back(POINT2);
935 points.push_back(POINT3);
938 std::ofstream sf(
"test_small.df", std::ios::out);
944 std::ifstream si(
"test_small.df", std::ios::in | std::ios::binary);
949 PERF_ORIGIN_Z, PERF_MAX_DIST,
false);
951 shapes::Sphere sphere(.5);
953 Eigen::Isometry3d
p = Eigen::Translation3d(0.5, 0.5, 0.5) * Eigen::Quaterniond(0.0, 0.0, 0.0, 1.0);
957 std::ofstream
f(
"test_big.df", std::ios::out);
962 std::ifstream i(
"test_big.df", std::ios::in);
969 std::ifstream i2(
"test_big.df", std::ios::in);
970 auto wt = std::chrono::system_clock::now();
972 std::cout <<
"Reconstruction for big file took " << (std::chrono::system_clock::now() - wt).count() <<
'\n';
976 int main(
int argc,
char** argv)
978 testing::InitGoogleTest(&argc, argv);
979 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)
void check_distance_field(const PropagationDistanceField &df, const EigenSTL::vector_Vector3d &points, int numX, int numY, int numZ, bool do_negs)
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)
int dist_sq(int x, int y, int z)
bool checkOctomapVersusDistanceField(const PropagationDistanceField &df, const octomap::OcTree &octree)
void printNeg(PropagationDistanceField &pdf, int numX, int numY, int numZ)
TEST(TestPropagationDistanceField, TestAddRemovePoints)
unsigned int countOccupiedCells(const PropagationDistanceField &df)