37 #include <gtest/gtest.h> 51 static const double WIDTH = 1.0;
53 static const double DEPTH = 1.0;
66 return x * x + y * y + z * z;
71 for (
int z = 0;
z < numZ;
z++)
73 for (
int y = 0;
y < numY;
y++)
75 for (
int x = 0;
x < numX;
x++)
79 std::cout << std::endl;
81 std::cout << std::endl;
83 for (
int z = 0;
z < numZ;
z++)
85 for (
int y = 0;
y < numY;
y++)
87 for (
int x = 0;
x < numX;
x++)
100 for (
int z = 0;
z < numZ;
z++)
102 for (
int y = 0;
y < numY;
y++)
104 for (
int x = 0;
x < numX;
x++)
108 std::cout << std::endl;
110 std::cout << std::endl;
136 std::cout <<
"Positive distance square ... negative distance square" << std::endl;
137 for (
int z = 0;
z < numZ;
z++)
139 std::cout <<
"Z=" <<
z << std::endl;
140 for (
int y = 0;
y < numY;
y++)
142 for (
int x = 0;
x < numX;
x++)
147 for (
int x = 0;
x < numX;
x++)
152 for (
int x = 0;
x < numX;
x++)
157 for (
int x = 0;
x < numX;
x++)
161 std::cout << std::endl;
163 std::cout << std::endl;
189 printf(
"Cell %d %d %d neg distances not equal %d %d\n",
x,
y,
z,
227 result = octree.
search(query_boundary);
237 std::cout <<
"No point at potential boundary query " << query.
x() <<
" " << query.
y() <<
" " << query.
z()
244 std::cout <<
"Disagreement at " << qx <<
" " << qy <<
" " << qz << std::endl;
256 unsigned int count = 0;
275 unsigned int count = 0;
276 for (octomap::OcTree::leaf_iterator it = octree.
begin_leafs(), end = octree.
end_leafs(); it != end; ++it)
280 std::cout <<
"Leaf node " << it.getX() <<
" " << it.getY() <<
" " << it.getZ() << std::endl;
289 int numY,
int numZ,
bool do_negs)
292 for (
unsigned int i = 0; i < points.size(); i++)
295 df.
worldToGrid(points[i].
x(), points[i].
y(), points[i].
z(), loc.x(), loc.y(), loc.z());
299 for (
int x = 0;
x < numX;
x++)
301 for (
int y = 0;
y < numY;
y++)
303 for (
int z = 0;
z < numZ;
z++)
310 for (
unsigned int i = 0; i < points_ind.size(); i++)
312 if (points_ind[i].
x() ==
x && points_ind[i].y() ==
y && points_ind[i].z() ==
z)
320 ASSERT_GT(ndsq, 0) <<
"Obstacle point " <<
x <<
" " <<
y <<
" " <<
z <<
" has zero negative value";
322 ASSERT_TRUE(found) <<
"Obstacle point " <<
x <<
" " <<
y <<
" " <<
z <<
" not found";
329 TEST(TestPropagationDistanceField, TestAddRemovePoints)
343 double tgx, tgy, tgz;
353 ROS_INFO_NAMED(
"distance_field",
"Adding %zu points", points.size());
362 old_points.push_back(
POINT1);
394 double dist_grad = df.
getDistanceGradient(wx, wy, wz, grad.x(), grad.y(), grad.z(), grad_in_bounds);
395 ASSERT_TRUE(grad_in_bounds) <<
x <<
" " <<
y <<
" " <<
z;
396 ASSERT_NEAR(dist, dist_grad, .0001);
399 double xscale = grad.x() / grad.norm();
400 double yscale = grad.y() / grad.norm();
401 double zscale = grad.z() / grad.norm();
403 double comp_x = wx - xscale * dist;
404 double comp_y = wy - yscale * dist;
405 double comp_z = wz - zscale * dist;
409 std::cout <<
"Dist " << dist << std::endl;
410 std::cout <<
"Cell " <<
x <<
" " <<
y <<
" " << z <<
" " << wx <<
" " << wy <<
" " << wz << std::endl;
411 std::cout <<
"Scale " << xscale <<
" " << yscale <<
" " << zscale << std::endl;
412 std::cout <<
"Grad " << grad.x() <<
" " << grad.y() <<
" " << grad.z() <<
" comp " << comp_x <<
" " 413 << comp_y <<
" " << comp_z << std::endl;
416 << dist <<
x <<
" " <<
y <<
" " << z <<
" " << grad.x() <<
" " << grad.y() <<
" " << grad.z() <<
" " 417 << xscale <<
" " << yscale <<
" " << zscale << std::endl;
419 <<
x <<
" " <<
y <<
" " << z <<
" " << grad.x() <<
" " << grad.y() <<
" " << grad.z() <<
" " << xscale
420 <<
" " << yscale <<
" " << zscale << std::endl;
422 <<
x <<
" " <<
y <<
" " << z <<
" " << grad.x() <<
" " << grad.y() <<
" " << grad.z() <<
" " << xscale
423 <<
" " << yscale <<
" " << zscale << std::endl;
431 TEST(TestSignedPropagationDistanceField, TestSignedAddRemovePoints)
451 double lwx, lwy, lwz;
452 double hwx, hwy, hwz;
457 for (
double x = lwx;
x <= hwx;
x += .1)
459 for (
double y = lwy;
y <= hwy;
y += .1)
461 for (
double z = lwz;
z <= hwz;
z += .1)
469 ROS_INFO_NAMED(
"distance_field",
"Adding %zu points", points.size());
480 rem_points.push_back(center_point);
490 for (
unsigned int i = 0; i < points.size(); i++)
492 if (points[i].
x() != center_point.x() || points[i].y() != center_point.y() || points[i].z() != center_point.z())
494 test_points.push_back(points[i]);
504 geometry_msgs::Pose p;
505 p.orientation.w = 1.0;
510 Eigen::Isometry3d p_eigen;
525 Eigen::Vector3i ncell_pos;
530 if (ncell ==
nullptr)
535 <<
"dist=" << dist <<
" xyz=" <<
x <<
" " <<
y <<
" " <<
z <<
" ncell=" << ncell_pos.x() <<
" " 536 << ncell_pos.y() <<
" " << ncell_pos.z() << std::endl;
538 else if (ncell_dist < 0)
541 <<
"dist=" << dist <<
" xyz=" <<
x <<
" " <<
y <<
" " <<
z <<
" ncell=" << ncell_pos.x() <<
" " 542 << ncell_pos.y() <<
" " << ncell_pos.z() << std::endl;
554 double dist_grad = gradient_df.
getDistanceGradient(wx, wy, wz, grad.x(), grad.y(), grad.z(), grad_in_bounds);
555 ASSERT_TRUE(grad_in_bounds) <<
x <<
" " <<
y <<
" " <<
z;
556 ASSERT_NEAR(dist, dist_grad, .0001);
561 EXPECT_GE(gradient_df.
getCell(ncell_pos.x(), ncell_pos.y(), ncell_pos.z()).distance_square_, 1)
562 <<
"dist=" << dist <<
" xyz=" <<
x <<
" " <<
y <<
" " << z <<
" grad=" << grad.x() <<
" " << grad.y()
563 <<
" " << grad.z() <<
" ncell=" << ncell_pos.x() <<
" " << ncell_pos.y() <<
" " << ncell_pos.z()
566 double grad_size_sq = grad.squaredNorm();
567 if (grad_size_sq < std::numeric_limits<double>::epsilon())
570 double oo_grad_size = 1.0 /
sqrt(grad_size_sq);
571 double xscale = grad.x() * oo_grad_size;
572 double yscale = grad.y() * oo_grad_size;
573 double zscale = grad.z() * oo_grad_size;
575 double comp_x = wx - xscale * dist;
576 double comp_y = wy - yscale * dist;
577 double comp_z = wz - zscale * dist;
579 int cell_x, cell_y, cell_z;
580 bool cell_in_bounds = gradient_df.
worldToGrid(comp_x, comp_y, comp_z, cell_x, cell_y, cell_z);
582 ASSERT_EQ(cell_in_bounds,
true);
592 << dist <<
" " <<
x <<
" " <<
y <<
" " << z <<
" " << grad.x() <<
" " << grad.y() <<
" " << grad.z()
593 <<
" " << xscale <<
" " << yscale <<
" " << zscale <<
" cell " << comp_x <<
" " << comp_y <<
" " << comp_z
601 TEST(TestSignedPropagationDistanceField, TestShape)
611 Eigen::Isometry3d p = Eigen::Translation3d(0.5, 0.5, 0.5) * Eigen::Quaterniond(0.0, 0.0, 0.0, 1.0);
612 Eigen::Isometry3d np = Eigen::Translation3d(0.7, 0.7, 0.7) * Eigen::Quaterniond(0.0, 0.0, 0.0, 1.0);
637 point_vec_union.insert(point_vec_union.end(), point_vec.begin(), point_vec.end());
661 TEST(TestSignedPropagationDistanceField, TestPerformance)
663 std::cout <<
"Creating distance field with " 665 <<
" entries" << std::endl;
670 std::cout <<
"Creating unsigned took " << (
ros::WallTime::now() - dt).toSec() << std::endl;
676 std::cout <<
"Creating signed took " << (
ros::WallTime::now() - dt).toSec() << std::endl;
681 Eigen::Quaterniond(0.0, 0.0, 0.0, 1.0);
683 Eigen::Quaterniond(0.0, 0.0, 0.0, 1.0);
687 std::cout <<
"Adding " << big_num_points <<
" points" << std::endl;
691 std::cout <<
"Adding to unsigned took " << (
ros::WallTime::now() - dt).toSec() <<
" avg " 696 std::cout <<
"Re-adding to unsigned took " << (
ros::WallTime::now() - dt).toSec() << std::endl;
700 std::cout <<
"Adding to signed took " << (
ros::WallTime::now() - dt).toSec() <<
" avg " 705 std::cout <<
"Moving in unsigned took " << (
ros::WallTime::now() - dt).toSec() << std::endl;
709 std::cout <<
"Moving in signed took " << (
ros::WallTime::now() - dt).toSec() << std::endl;
713 std::cout <<
"Removing from unsigned took " << (
ros::WallTime::now() - dt).toSec() << std::endl;
717 std::cout <<
"Removing from signed took " << (
ros::WallTime::now() - dt).toSec() << std::endl;
724 unsigned int small_num_points = (13) * (13) * (3);
726 std::cout <<
"Adding " << small_num_points <<
" points" << std::endl;
730 std::cout <<
"Adding to unsigned took " << (
ros::WallTime::now() - dt).toSec() <<
" avg " 735 std::cout <<
"Adding to signed took " << (
ros::WallTime::now() - dt).toSec() <<
" avg " 740 std::cout <<
"Moving in unsigned took " << (
ros::WallTime::now() - dt).toSec() << std::endl;
744 std::cout <<
"Moving in signed took " << (
ros::WallTime::now() - dt).toSec() << std::endl;
754 unsigned int count = 0;
763 bool valid = worstdfu.
gridToWorld(
x,
y,
z, loc.x(), loc.y(), loc.z());
770 bad_vec.push_back(loc);
778 printf(
"Time for unsigned adding %u uniform points is %g average %g\n", (
unsigned int)bad_vec.size(), wd.
toSec(),
779 wd.
toSec() / (bad_vec.size() * 1.0));
783 printf(
"Time for signed adding %u uniform points is %g average %g\n", (
unsigned int)bad_vec.size(), wd.
toSec(),
784 wd.
toSec() / (bad_vec.size() * 1.0));
787 TEST(TestSignedPropagationDistanceField, TestOcTree)
794 unsigned int count = 0;
795 for (
float x = 1.01;
x < 1.5;
x += .02)
797 for (
float y = 1.01;
y < 1.5;
y += .02)
799 for (
float z = 1.01;
z < 1.5;
z += .02, count++)
808 for (
float x = 2.51;
x < 3.5;
x += .02)
810 for (
float y = 1.01;
y < 3.5;
y += .02)
812 for (
float z = 1.01;
z < 3.5;
z += .02, count++)
820 std::cout <<
"OcTree nodes " << count << std::endl;
826 for (
float x = .01;
x < .50;
x += .02)
828 for (
float y = .01;
y < .50;
y += .02)
830 for (
float z = .01;
z < .50;
z += .02, count++)
867 tree_shape->updateNode(tpoint1,
true);
868 tree_shape->updateNode(tpoint2,
true);
869 tree_shape->updateNode(tpoint3,
true);
871 std::shared_ptr<shapes::OcTree> shape_oc(
new shapes::OcTree(tree_shape));
884 TEST(TestSignedPropagationDistanceField, TestReadWrite)
894 std::ofstream sf(
"test_small.df", std::ios::out);
900 std::ifstream si(
"test_small.df", std::ios::in | std::ios::binary);
909 Eigen::Isometry3d p = Eigen::Translation3d(0.5, 0.5, 0.5) * Eigen::Quaterniond(0.0, 0.0, 0.0, 1.0);
913 std::ofstream
f(
"test_big.df", std::ios::out);
918 std::ifstream i(
"test_big.df", std::ios::in);
925 std::ifstream i2(
"test_big.df", std::ios::in);
928 std::cout <<
"Reconstruction for big file took " << (
ros::WallTime::now() - wt).toSec() << std::endl;
932 int main(
int argc,
char** argv)
934 testing::InitGoogleTest(&argc, argv);
935 return RUN_ALL_TESTS();
bool areDistanceFieldsDistancesEqual(const PropagationDistanceField &df1, const PropagationDistanceField &df2)
static const Eigen::Vector3d POINT3(0.4, 0.0, 0.0)
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...
static const double DEPTH
#define ROS_INFO_NAMED(name,...)
void check_distance_field(const PropagationDistanceField &df, const EigenSTL::vector_Vector3d &points, int numX, int numY, int numZ, bool do_negs)
void setPose(const Eigen::Isometry3d &pose)
int getZNumCells() const override
Gets the number of cells along the Z axis.
unsigned int countLeafNodes(const octomap::OcTree &octree)
Vec3fX< details::Vec3Data< double > > Vector3d
#define ROS_WARN_NAMED(name,...)
bool writeToStream(std::ostream &stream) const override
Writes the contents of the distance field to the supplied stream.
std::vector< Eigen::Vector3d, Eigen::aligned_allocator< Eigen::Vector3d > > vector_Vector3d
static const double ORIGIN_Z
const PropDistanceFieldVoxel & getCell(int x, int y, int z) const
Gets full cell data given an index.
int distance_square_
Distance in cells to the closest obstacle, squared.
static const unsigned int UNIFORM_DISTANCE
virtual OcTreeNode * updateNode(const OcTreeKey &key, float log_odds_update, bool lazy_eval=false)
static const double RESOLUTION
Structure that holds voxel information for the DistanceField. Will be used in VoxelGrid.
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...
void addPointsToField(const EigenSTL::vector_Vector3d &points) override
Add a set of obstacle points to the distance field, updating distance values accordingly. The distance field may already contain obstacle cells.
#define EXPECT_NEAR(a, b, prec)
const PropDistanceFieldVoxel * getNearestCell(int x, int y, int z, double &dist, Eigen::Vector3i &pos) const
Gets nearest surface cell and returns distance to it.
Eigen::Vector3i closest_point_
Closest occupied cell.
Eigen::Vector3i closest_negative_point_
Closest unoccupied cell.
int getXNumCells() const override
Gets the number of cells along the X axis.
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 ...
static const double PERF_WIDTH
leaf_iterator begin_leafs(unsigned char maxDepth=0) const
#define EXPECT_FALSE(args)
static const double PERF_DEPTH
OcTreeNode * search(double x, double y, double z, unsigned int depth=0) const
static const double PERF_HEIGHT
void reset() override
Resets the entire distance field to max_distance for positive values and zero for negative values...
static const double ORIGIN_X
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 printBoth(PropagationDistanceField &pdf, int numX, int numY, int numZ)
static const double PERF_ORIGIN_Y
static const double WIDTH
Body * createBodyFromShape(const shapes::Shape *shape)
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...
static const Eigen::Vector3d POINT1(0.1, 0.0, 0.0)
void fromMsg(const A &, B &b)
int main(int argc, char **argv)
TEST(TestPropagationDistanceField, TestAddRemovePoints)
std::vector< Eigen::Vector3i, Eigen::aligned_allocator< Eigen::Vector3i > > vector_Vector3i
int getYNumCells() const override
Gets the number of cells along the Y axis.
unsigned int countOccupiedCells(const PropagationDistanceField &df)
INLINE Rall1d< T, V, S > sqrt(const Rall1d< T, V, S > &arg)
double getUninitializedDistance() const override
Gets a distance value for an invalid cell.
static const double PERF_ORIGIN_X
double getResolution() const
Gets the resolution of the distance field in meters.
Namespace for holding classes that generate distance fields.
const leaf_iterator end_leafs() const
int dist_sq(int x, int y, int z)
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...
static const Eigen::Vector3d POINT2(0.0, 0.1, 0.2)
static const double HEIGHT
double getDistance(double x, double y, double z) const override
Get the distance value associated with the cell indicated by the world coordinate. If the cell is invalid, max_distance will be returned. If running without negative distances, all obstacle cells will have zero distance. If running with negative distances, the distance will be between -max_distance and max_distance, with no values having a 0 distance.
bool checkOctomapVersusDistanceField(const PropagationDistanceField &df, const octomap::OcTree &octree)
void removePointsFromField(const EigenSTL::vector_Vector3d &points) override
Remove a set of obstacle points from the distance field, updating distance values accordingly...
static const double PERF_ORIGIN_Z
int negative_distance_square_
Distance in cells to the nearest unoccupied cell, squared.
void removeShapeFromField(const shapes::Shape *shape, const Eigen::Isometry3d &pose)
All points corresponding to the shape are removed from the distance field.
static const double MAX_DIST
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...
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...
A DistanceField implementation that uses a vector propagation method. Distances propagate outward fro...
bool isNodeOccupied(const OcTreeNode *occupancyNode) const
void printNeg(PropagationDistanceField &pdf, int numX, int numY, int numZ)
void printPointCoords(const Eigen::Vector3i &p)
#define EXPECT_TRUE(args)
static const double PERF_MAX_DIST
static const double ORIGIN_Y
static const double PERF_RESOLUTION
void print(PropagationDistanceField &pdf, int numX, int numY, int numZ)