38 #include <visualization_msgs/msg/marker.hpp>
39 #include <boost/iostreams/filtering_stream.hpp>
40 #include <boost/iostreams/copy.hpp>
41 #include <boost/iostreams/filter/zlib.hpp>
42 #include <rclcpp/logger.hpp>
43 #include <rclcpp/logging.hpp>
48 static const rclcpp::Logger LOGGER = rclcpp::get_logger(
"moveit_distance_field.propagation_distance_field");
51 double origin_x,
double origin_y,
double origin_z,
52 double max_distance,
bool propagate_negative)
53 :
DistanceField(size_x, size_y, size_z, resolution, origin_x, origin_y, origin_z)
54 , propagate_negative_(propagate_negative)
55 , max_distance_(max_distance)
61 const octomap::point3d& bbx_max,
double max_distance,
62 bool propagate_negative_distances)
63 :
DistanceField(bbx_max.
x() - bbx_min.
x(), bbx_max.
y() - bbx_min.
y(), bbx_max.
z() - bbx_min.
z(),
64 octree.getResolution(), bbx_min.
x(), bbx_min.
y(), bbx_min.
z())
65 , propagate_negative_(propagate_negative_distances)
66 , max_distance_(max_distance)
74 bool propagate_negative_distances)
75 :
DistanceField(0, 0, 0, 0, 0, 0, 0), propagate_negative_(propagate_negative_distances), max_distance_(max_distance)
80 void PropagationDistanceField::initialize()
89 bucket_queue_.resize(max_distance_sq_ + 1);
90 negative_bucket_queue_.resize(max_distance_sq_ + 1);
93 sqrt_table_.resize(max_distance_sq_ + 1);
94 for (
int i = 0; i <= max_distance_sq_; ++i)
100 void PropagationDistanceField::print(
const VoxelSet& set)
102 RCLCPP_DEBUG(LOGGER,
"[");
103 VoxelSet::const_iterator it;
104 for (it = set.begin(); it != set.end(); ++it)
106 Eigen::Vector3i loc1 = *it;
107 RCLCPP_DEBUG(LOGGER,
"%d, %d, %d ", loc1.x(), loc1.y(), loc1.z());
109 RCLCPP_DEBUG(LOGGER,
"] size=%u\n", (
unsigned int)set.size());
112 void PropagationDistanceField::print(
const EigenSTL::vector_Vector3d& points)
114 RCLCPP_DEBUG(LOGGER,
"[");
115 EigenSTL::vector_Vector3d::const_iterator it;
116 for (it = points.begin(); it != points.end(); ++it)
119 RCLCPP_DEBUG(LOGGER,
"%g, %g, %g ", loc1.x(), loc1.y(), loc1.z());
121 RCLCPP_DEBUG(LOGGER,
"] size=%u\n", (
unsigned int)points.size());
125 const EigenSTL::vector_Vector3d& new_points)
127 VoxelSet old_point_set;
130 Eigen::Vector3i voxel_loc;
131 bool valid =
worldToGrid(old_point.x(), old_point.y(), old_point.z(), voxel_loc.x(), voxel_loc.y(), voxel_loc.z());
134 old_point_set.insert(voxel_loc);
138 VoxelSet new_point_set;
141 Eigen::Vector3i voxel_loc;
142 bool valid =
worldToGrid(new_point.x(), new_point.y(), new_point.z(), voxel_loc.x(), voxel_loc.y(), voxel_loc.z());
145 new_point_set.insert(voxel_loc);
151 std::set_difference(old_point_set.begin(), old_point_set.end(), new_point_set.begin(), new_point_set.end(),
152 std::inserter(old_not_new, old_not_new.end()), comp);
155 std::set_difference(new_point_set.begin(), new_point_set.end(), old_point_set.begin(), old_point_set.end(),
156 std::inserter(new_not_old, new_not_old.end()), comp);
159 for (Eigen::Vector3i& voxel_loc : new_not_old)
161 if (voxel_grid_->getCell(voxel_loc.x(), voxel_loc.y(), voxel_loc.z()).distance_square_ != 0)
163 new_not_in_current.push_back(voxel_loc);
167 removeObstacleVoxels(old_not_new);
168 addNewObstacleVoxels(new_not_in_current);
178 Eigen::Vector3i voxel_loc;
179 bool valid =
worldToGrid(point.x(), point.y(), point.z(), voxel_loc.x(), voxel_loc.y(), voxel_loc.z());
183 if (voxel_grid_->getCell(voxel_loc.x(), voxel_loc.y(), voxel_loc.z()).distance_square_ > 0)
185 voxel_points.push_back(voxel_loc);
189 addNewObstacleVoxels(voxel_points);
200 Eigen::Vector3i voxel_loc;
201 bool valid =
worldToGrid(point.x(), point.y(), point.z(), voxel_loc.x(), voxel_loc.y(), voxel_loc.z());
205 voxel_points.push_back(voxel_loc);
212 removeObstacleVoxels(voxel_points);
217 int initial_update_direction = getDirectionNumber(0, 0, 0);
218 bucket_queue_[0].reserve(voxel_points.size());
220 if (propagate_negative_)
223 negative_bucket_queue_[0].reserve(voxel_points.size());
226 for (
const Eigen::Vector3i& voxel_point : voxel_points)
228 PropDistanceFieldVoxel& voxel = voxel_grid_->getCell(voxel_point.x(), voxel_point.y(), voxel_point.z());
229 const Eigen::Vector3i& loc = voxel_point;
230 voxel.distance_square_ = 0;
231 voxel.closest_point_ = loc;
232 voxel.update_direction_ = initial_update_direction;
233 bucket_queue_[0].push_back(loc);
234 if (propagate_negative_)
236 voxel.negative_distance_square_ = max_distance_sq_;
240 negative_stack.push_back(loc);
245 if (propagate_negative_)
247 while (!negative_stack.empty())
249 Eigen::Vector3i loc = negative_stack.back();
250 negative_stack.pop_back();
252 for (
int neighbor = 0; neighbor < 27; ++neighbor)
254 Eigen::Vector3i diff = getLocationDifference(neighbor);
255 Eigen::Vector3i nloc(loc.x() + diff.x(), loc.y() + diff.y(), loc.z() + diff.z());
259 PropDistanceFieldVoxel& nvoxel = voxel_grid_->getCell(nloc.x(), nloc.y(), nloc.z());
260 Eigen::Vector3i& close_point = nvoxel.closest_negative_point_;
261 if (!
isCellValid(close_point.x(), close_point.y(), close_point.z()))
265 PropDistanceFieldVoxel& closest_point_voxel =
266 voxel_grid_->getCell(close_point.x(), close_point.y(), close_point.z());
269 if (closest_point_voxel.negative_distance_square_ != 0)
275 if (nvoxel.negative_distance_square_ != max_distance_sq_)
277 nvoxel.negative_distance_square_ = max_distance_sq_;
281 negative_stack.push_back(nloc);
287 nvoxel.negative_update_direction_ = initial_update_direction;
288 negative_bucket_queue_[0].push_back(nloc);
302 int initial_update_direction = getDirectionNumber(0, 0, 0);
305 bucket_queue_[0].reserve(voxel_points.size());
306 if (propagate_negative_)
309 negative_bucket_queue_[0].reserve(voxel_points.size());
320 for (
const Eigen::Vector3i& voxel_point : voxel_points)
322 PropDistanceFieldVoxel& voxel = voxel_grid_->getCell(voxel_point.x(), voxel_point.y(), voxel_point.z());
323 voxel.distance_square_ = max_distance_sq_;
324 voxel.closest_point_ = voxel_point;
325 voxel.update_direction_ = initial_update_direction;
326 stack.push_back(voxel_point);
327 if (propagate_negative_)
329 voxel.negative_distance_square_ = 0.0;
330 voxel.closest_negative_point_ = voxel_point;
331 voxel.negative_update_direction_ = initial_update_direction;
332 negative_bucket_queue_[0].push_back(voxel_point);
337 while (!stack.empty())
339 Eigen::Vector3i loc = stack.back();
342 for (
int neighbor = 0; neighbor < 27; ++neighbor)
344 Eigen::Vector3i diff = getLocationDifference(neighbor);
345 Eigen::Vector3i nloc(loc.x() + diff.x(), loc.y() + diff.y(), loc.z() + diff.z());
349 PropDistanceFieldVoxel& nvoxel = voxel_grid_->getCell(nloc.x(), nloc.y(), nloc.z());
350 Eigen::Vector3i& close_point = nvoxel.closest_point_;
351 if (!
isCellValid(close_point.x(), close_point.y(), close_point.z()))
355 PropDistanceFieldVoxel& closest_point_voxel =
356 voxel_grid_->getCell(close_point.x(), close_point.y(), close_point.z());
358 if (closest_point_voxel.distance_square_ != 0)
360 if (nvoxel.distance_square_ != max_distance_sq_)
362 nvoxel.distance_square_ = max_distance_sq_;
363 nvoxel.closest_point_ = nloc;
364 nvoxel.update_direction_ = initial_update_direction;
365 stack.push_back(nloc);
370 nvoxel.update_direction_ = initial_update_direction;
371 bucket_queue_[0].push_back(nloc);
378 if (propagate_negative_)
384 void PropagationDistanceField::propagatePositive()
387 for (
unsigned int i = 0; i < bucket_queue_.size(); ++i)
389 EigenSTL::vector_Vector3i::iterator list_it = bucket_queue_[i].begin();
390 EigenSTL::vector_Vector3i::iterator list_end = bucket_queue_[i].end();
391 for (; list_it != list_end; ++list_it)
393 const Eigen::Vector3i& loc = *list_it;
394 PropDistanceFieldVoxel* vptr = &voxel_grid_->getCell(loc.x(), loc.y(), loc.z());
403 if (vptr->update_direction_ < 0 || vptr->update_direction_ > 26)
405 RCLCPP_ERROR(LOGGER,
"PROGRAMMING ERROR: Invalid update direction detected: %d", vptr->update_direction_);
409 neighborhood = &neighborhoods_[
d][vptr->update_direction_];
411 for (
const Eigen::Vector3i& diff : *neighborhood)
413 Eigen::Vector3i nloc(loc.x() + diff.x(), loc.y() + diff.y(), loc.z() + diff.z());
419 PropDistanceFieldVoxel* neighbor = &voxel_grid_->getCell(nloc.x(), nloc.y(), nloc.z());
420 int new_distance_sq = (vptr->closest_point_ - nloc).squaredNorm();
421 if (new_distance_sq > max_distance_sq_)
424 if (new_distance_sq < neighbor->distance_square_)
427 neighbor->distance_square_ = new_distance_sq;
428 neighbor->closest_point_ = vptr->closest_point_;
429 neighbor->update_direction_ = getDirectionNumber(diff.x(), diff.y(), diff.z());
432 bucket_queue_[new_distance_sq].push_back(nloc);
436 bucket_queue_[i].clear();
440 void PropagationDistanceField::propagateNegative()
443 for (
unsigned int i = 0; i < negative_bucket_queue_.size(); ++i)
445 EigenSTL::vector_Vector3i::iterator list_it = negative_bucket_queue_[i].begin();
446 EigenSTL::vector_Vector3i::iterator list_end = negative_bucket_queue_[i].end();
447 for (; list_it != list_end; ++list_it)
449 const Eigen::Vector3i& loc = *list_it;
450 PropDistanceFieldVoxel* vptr = &voxel_grid_->getCell(loc.x(), loc.y(), loc.z());
460 if (vptr->negative_update_direction_ < 0 || vptr->negative_update_direction_ > 26)
462 RCLCPP_ERROR(LOGGER,
"PROGRAMMING ERROR: Invalid update direction detected: %d", vptr->update_direction_);
466 neighborhood = &neighborhoods_[
d][vptr->negative_update_direction_];
468 for (
const Eigen::Vector3i& diff : *neighborhood)
470 Eigen::Vector3i nloc(loc.x() + diff.x(), loc.y() + diff.y(), loc.z() + diff.z());
476 PropDistanceFieldVoxel* neighbor = &voxel_grid_->getCell(nloc.x(), nloc.y(), nloc.z());
477 int new_distance_sq = (vptr->closest_negative_point_ - nloc).squaredNorm();
478 if (new_distance_sq > max_distance_sq_)
482 if (new_distance_sq < neighbor->negative_distance_square_)
487 neighbor->negative_distance_square_ = new_distance_sq;
488 neighbor->closest_negative_point_ = vptr->closest_negative_point_;
489 neighbor->negative_update_direction_ = getDirectionNumber(diff.x(), diff.y(), diff.z());
492 negative_bucket_queue_[new_distance_sq].push_back(nloc);
496 negative_bucket_queue_[i].clear();
520 void PropagationDistanceField::initNeighborhoods()
523 direction_number_to_direction_.resize(27);
524 for (
int dx = -1; dx <= 1; ++dx)
526 for (
int dy = -1; dy <= 1; ++dy)
528 for (
int dz = -1; dz <= 1; ++dz)
530 int direction_number = getDirectionNumber(dx, dy, dz);
531 Eigen::Vector3i n_point(dx, dy, dz);
532 direction_number_to_direction_[direction_number] = n_point;
537 neighborhoods_.resize(2);
538 for (
int n = 0; n < 2; ++n)
540 neighborhoods_[n].resize(27);
542 for (
int dx = -1; dx <= 1; ++dx)
544 for (
int dy = -1; dy <= 1; ++dy)
546 for (
int dz = -1; dz <= 1; ++dz)
548 int direction_number = getDirectionNumber(dx, dy, dz);
550 for (
int tdx = -1; tdx <= 1; ++tdx)
552 for (
int tdy = -1; tdy <= 1; ++tdy)
554 for (
int tdz = -1; tdz <= 1; ++tdz)
556 if (tdx == 0 && tdy == 0 && tdz == 0)
560 if ((abs(tdx) + abs(tdy) + abs(tdz)) != 1)
562 if (dx * tdx < 0 || dy * tdy < 0 || dz * tdz < 0)
565 Eigen::Vector3i n_point(tdx, tdy, tdz);
566 neighborhoods_[n][direction_number].push_back(n_point);
578 int PropagationDistanceField::getDirectionNumber(
int dx,
int dy,
int dz)
const
580 return (dx + 1) * 9 + (dy + 1) * 3 + dz + 1;
583 Eigen::Vector3i PropagationDistanceField::getLocationDifference(
int directionNumber)
const
585 return direction_number_to_direction_[directionNumber];
600 return voxel_grid_->isCellValid(
x,
y,
z);
605 return voxel_grid_->getNumCells(
DIM_X);
610 return voxel_grid_->getNumCells(
DIM_Y);
615 return voxel_grid_->getNumCells(
DIM_Z);
620 voxel_grid_->gridToWorld(
x,
y,
z, world_x, world_y, world_z);
626 return voxel_grid_->worldToGrid(world_x, world_y, world_z,
x,
y,
z);
632 os <<
"size_x: " <<
size_x_ <<
'\n';
633 os <<
"size_y: " <<
size_y_ <<
'\n';
634 os <<
"size_z: " <<
size_z_ <<
'\n';
641 boost::iostreams::filtering_ostream out;
642 out.push(boost::iostreams::zlib_compressor());
645 for (
unsigned int x = 0; x < static_cast<unsigned int>(
getXNumCells()); ++
x)
647 for (
unsigned int y = 0; y < static_cast<unsigned int>(
getYNumCells()); ++
y)
649 for (
unsigned int z = 0; z < static_cast<unsigned int>(
getZNumCells());
z += 8)
651 std::bitset<8> bs(0);
652 unsigned int zv = std::min((
unsigned int)8,
getZNumCells() -
z);
653 for (
unsigned int zi = 0; zi < zv; ++zi)
655 if (
getCell(
x,
y,
z + zi).distance_square_ == 0)
661 out.write((
char*)&bs,
sizeof(
char));
677 if (temp !=
"resolution:")
682 if (temp !=
"size_x:")
687 if (temp !=
"size_y:")
692 if (temp !=
"size_z:")
697 if (temp !=
"origin_x:")
702 if (temp !=
"origin_y:")
707 if (temp !=
"origin_z:")
720 boost::iostreams::filtering_istream in;
721 in.push(boost::iostreams::zlib_decompressor());
727 for (
unsigned int x = 0; x < static_cast<unsigned int>(
getXNumCells()); ++
x)
729 for (
unsigned int y = 0; y < static_cast<unsigned int>(
getYNumCells()); ++
y)
731 for (
unsigned int z = 0; z < static_cast<unsigned int>(
getZNumCells());
z += 8)
739 std::bitset<8> inbit((
unsigned long long)inchar);
740 unsigned int zv = std::min((
unsigned int)8,
getZNumCells() -
z);
741 for (
unsigned int zi = 0; zi < zv; ++zi)
746 obs_points.push_back(Eigen::Vector3i(
x,
y,
z + zi));
752 addNewObstacleVoxels(obs_points);
DistanceField is an abstract base class for computing distances from sets of 3D obstacle points....
double resolution_
Resolution of the distance field.
double size_z_
Z size of the distance field.
double origin_z_
Z origin of the distance field.
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 origin_x_
X origin of the distance field.
double size_y_
Y size of the distance field.
double size_x_
X size of the distance field.
double origin_y_
Y origin of the distance field.
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.
bool readFromStream(std::istream &stream) override
Reads, parameterizes, and populates the distance field based on the supplied stream.
bool isCellValid(int x, int y, int z) const override
Determines whether or not the cell associated with the supplied indices is valid for this distance fi...
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 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.
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...
PropagationDistanceField(double size_x, double size_y, double size_z, double resolution, double origin_x, double origin_y, double origin_z, double max_distance, bool propagate_negative_distances=false)
Constructor that initializes entire distance field to empty - all cells will be assigned maximum dist...
std::vector< Eigen::Vector3i, Eigen::aligned_allocator< Eigen::Vector3i > > vector_Vector3i
Namespace for holding classes that generate distance fields.
Vec3fX< details::Vec3Data< double > > Vector3d
Struct for sorting type Eigen::Vector3i for use in sorted std containers. Sorts in z order,...
Structure that holds voxel information for the DistanceField. Will be used in VoxelGrid.
Eigen::Vector3i closest_negative_point_
Closest unoccupied cell.
static const int UNINITIALIZED
Value that represents an uninitialized voxel.
int negative_distance_square_
Distance in cells to the nearest unoccupied cell, squared.