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>
57 double origin_x,
double origin_y,
double origin_z,
58 double max_distance,
bool propagate_negative)
59 :
DistanceField(size_x, size_y, size_z, resolution, origin_x, origin_y, origin_z)
60 , propagate_negative_(propagate_negative)
61 , max_distance_(max_distance)
67 const octomap::point3d& bbx_max,
double max_distance,
68 bool propagate_negative_distances)
69 :
DistanceField(bbx_max.x() - bbx_min.x(), bbx_max.y() - bbx_min.y(), bbx_max.z() - bbx_min.z(),
70 octree.getResolution(), bbx_min.x(), bbx_min.y(), bbx_min.z())
71 , propagate_negative_(propagate_negative_distances)
72 , max_distance_(max_distance)
80 bool propagate_negative_distances)
81 :
DistanceField(0, 0, 0, 0, 0, 0, 0), propagate_negative_(propagate_negative_distances), max_distance_(max_distance)
86void PropagationDistanceField::initialize()
95 bucket_queue_.resize(max_distance_sq_ + 1);
96 negative_bucket_queue_.resize(max_distance_sq_ + 1);
99 sqrt_table_.resize(max_distance_sq_ + 1);
100 for (
int i = 0; i <= max_distance_sq_; ++i)
106void PropagationDistanceField::print(
const VoxelSet& set)
108 RCLCPP_DEBUG(getLogger(),
"[");
109 VoxelSet::const_iterator it;
110 for (it = set.begin(); it != set.end(); ++it)
112 Eigen::Vector3i loc1 = *it;
113 RCLCPP_DEBUG(getLogger(),
"%d, %d, %d ", loc1.x(), loc1.y(), loc1.z());
115 RCLCPP_DEBUG(
getLogger(),
"] size=%u\n",
static_cast<unsigned int>(set.size()));
118void PropagationDistanceField::print(
const EigenSTL::vector_Vector3d& points)
121 EigenSTL::vector_Vector3d::const_iterator it;
122 for (it = points.begin(); it != points.end(); ++it)
124 Eigen::Vector3d loc1 = *it;
125 RCLCPP_DEBUG(
getLogger(),
"%g, %g, %g ", loc1.x(), loc1.y(), loc1.z());
127 RCLCPP_DEBUG(
getLogger(),
"] size=%u\n",
static_cast<unsigned int>(points.size()));
131 const EigenSTL::vector_Vector3d& new_points)
133 VoxelSet old_point_set;
134 for (
const Eigen::Vector3d& old_point : old_points)
136 Eigen::Vector3i voxel_loc;
137 bool valid =
worldToGrid(old_point.x(), old_point.y(), old_point.z(), voxel_loc.x(), voxel_loc.y(), voxel_loc.z());
140 old_point_set.insert(voxel_loc);
144 VoxelSet new_point_set;
145 for (
const Eigen::Vector3d& new_point : new_points)
147 Eigen::Vector3i voxel_loc;
148 bool valid =
worldToGrid(new_point.x(), new_point.y(), new_point.z(), voxel_loc.x(), voxel_loc.y(), voxel_loc.z());
151 new_point_set.insert(voxel_loc);
157 std::set_difference(old_point_set.begin(), old_point_set.end(), new_point_set.begin(), new_point_set.end(),
158 std::inserter(old_not_new, old_not_new.end()), comp);
161 std::set_difference(new_point_set.begin(), new_point_set.end(), old_point_set.begin(), old_point_set.end(),
162 std::inserter(new_not_old, new_not_old.end()), comp);
165 for (Eigen::Vector3i& voxel_loc : new_not_old)
167 if (voxel_grid_->getCell(voxel_loc.x(), voxel_loc.y(), voxel_loc.z()).distance_square_ != 0)
169 new_not_in_current.push_back(voxel_loc);
173 removeObstacleVoxels(old_not_new);
174 addNewObstacleVoxels(new_not_in_current);
181 for (
const Eigen::Vector3d& point : points)
184 Eigen::Vector3i voxel_loc;
185 bool valid =
worldToGrid(point.x(), point.y(), point.z(), voxel_loc.x(), voxel_loc.y(), voxel_loc.z());
189 if (voxel_grid_->getCell(voxel_loc.x(), voxel_loc.y(), voxel_loc.z()).distance_square_ > 0)
191 voxel_points.push_back(voxel_loc);
195 addNewObstacleVoxels(voxel_points);
203 for (
const Eigen::Vector3d& point : points)
206 Eigen::Vector3i voxel_loc;
207 bool valid =
worldToGrid(point.x(), point.y(), point.z(), voxel_loc.x(), voxel_loc.y(), voxel_loc.z());
211 voxel_points.push_back(voxel_loc);
218 removeObstacleVoxels(voxel_points);
223 int initial_update_direction = getDirectionNumber(0, 0, 0);
224 bucket_queue_[0].reserve(voxel_points.size());
226 if (propagate_negative_)
229 negative_bucket_queue_[0].reserve(voxel_points.size());
232 for (
const Eigen::Vector3i& voxel_point : voxel_points)
234 PropDistanceFieldVoxel& voxel = voxel_grid_->getCell(voxel_point.x(), voxel_point.y(), voxel_point.z());
235 const Eigen::Vector3i& loc = voxel_point;
236 voxel.distance_square_ = 0;
237 voxel.closest_point_ = loc;
238 voxel.update_direction_ = initial_update_direction;
239 bucket_queue_[0].push_back(loc);
240 if (propagate_negative_)
242 voxel.negative_distance_square_ = max_distance_sq_;
246 negative_stack.push_back(loc);
251 if (propagate_negative_)
253 while (!negative_stack.empty())
255 Eigen::Vector3i loc = negative_stack.back();
256 negative_stack.pop_back();
258 for (
int neighbor = 0; neighbor < 27; ++neighbor)
260 Eigen::Vector3i diff = getLocationDifference(neighbor);
261 Eigen::Vector3i nloc(loc.x() + diff.x(), loc.y() + diff.y(), loc.z() + diff.z());
265 PropDistanceFieldVoxel& nvoxel = voxel_grid_->getCell(nloc.x(), nloc.y(), nloc.z());
266 Eigen::Vector3i& close_point = nvoxel.closest_negative_point_;
267 if (!
isCellValid(close_point.x(), close_point.y(), close_point.z()))
271 PropDistanceFieldVoxel& closest_point_voxel =
272 voxel_grid_->getCell(close_point.x(), close_point.y(), close_point.z());
275 if (closest_point_voxel.negative_distance_square_ != 0)
281 if (nvoxel.negative_distance_square_ != max_distance_sq_)
283 nvoxel.negative_distance_square_ = max_distance_sq_;
287 negative_stack.push_back(nloc);
293 nvoxel.negative_update_direction_ = initial_update_direction;
294 negative_bucket_queue_[0].push_back(nloc);
308 int initial_update_direction = getDirectionNumber(0, 0, 0);
311 bucket_queue_[0].reserve(voxel_points.size());
312 if (propagate_negative_)
315 negative_bucket_queue_[0].reserve(voxel_points.size());
326 for (
const Eigen::Vector3i& voxel_point : voxel_points)
328 PropDistanceFieldVoxel& voxel = voxel_grid_->getCell(voxel_point.x(), voxel_point.y(), voxel_point.z());
329 voxel.distance_square_ = max_distance_sq_;
330 voxel.closest_point_ = voxel_point;
331 voxel.update_direction_ = initial_update_direction;
332 stack.push_back(voxel_point);
333 if (propagate_negative_)
335 voxel.negative_distance_square_ = 0.0;
336 voxel.closest_negative_point_ = voxel_point;
337 voxel.negative_update_direction_ = initial_update_direction;
338 negative_bucket_queue_[0].push_back(voxel_point);
343 while (!stack.empty())
345 Eigen::Vector3i loc = stack.back();
348 for (
int neighbor = 0; neighbor < 27; ++neighbor)
350 Eigen::Vector3i diff = getLocationDifference(neighbor);
351 Eigen::Vector3i nloc(loc.x() + diff.x(), loc.y() + diff.y(), loc.z() + diff.z());
355 PropDistanceFieldVoxel& nvoxel = voxel_grid_->getCell(nloc.x(), nloc.y(), nloc.z());
356 Eigen::Vector3i& close_point = nvoxel.closest_point_;
357 if (!
isCellValid(close_point.x(), close_point.y(), close_point.z()))
361 PropDistanceFieldVoxel& closest_point_voxel =
362 voxel_grid_->getCell(close_point.x(), close_point.y(), close_point.z());
364 if (closest_point_voxel.distance_square_ != 0)
366 if (nvoxel.distance_square_ != max_distance_sq_)
368 nvoxel.distance_square_ = max_distance_sq_;
369 nvoxel.closest_point_ = nloc;
370 nvoxel.update_direction_ = initial_update_direction;
371 stack.push_back(nloc);
376 nvoxel.update_direction_ = initial_update_direction;
377 bucket_queue_[0].push_back(nloc);
384 if (propagate_negative_)
390void PropagationDistanceField::propagatePositive()
393 for (
unsigned int i = 0; i < bucket_queue_.size(); ++i)
395 EigenSTL::vector_Vector3i::iterator list_it = bucket_queue_[i].begin();
396 EigenSTL::vector_Vector3i::iterator list_end = bucket_queue_[i].end();
397 for (; list_it != list_end; ++list_it)
399 const Eigen::Vector3i& loc = *list_it;
400 PropDistanceFieldVoxel* vptr = &voxel_grid_->getCell(loc.x(), loc.y(), loc.z());
409 if (vptr->update_direction_ < 0 || vptr->update_direction_ > 26)
411 RCLCPP_ERROR(
getLogger(),
"PROGRAMMING ERROR: Invalid update direction detected: %d", vptr->update_direction_);
415 neighborhood = &neighborhoods_[d][vptr->update_direction_];
417 for (
const Eigen::Vector3i& diff : *neighborhood)
419 Eigen::Vector3i nloc(loc.x() + diff.x(), loc.y() + diff.y(), loc.z() + diff.z());
425 PropDistanceFieldVoxel* neighbor = &voxel_grid_->getCell(nloc.x(), nloc.y(), nloc.z());
426 int new_distance_sq = (vptr->closest_point_ - nloc).squaredNorm();
427 if (new_distance_sq > max_distance_sq_)
430 if (new_distance_sq < neighbor->distance_square_)
433 neighbor->distance_square_ = new_distance_sq;
434 neighbor->closest_point_ = vptr->closest_point_;
435 neighbor->update_direction_ = getDirectionNumber(diff.x(), diff.y(), diff.z());
438 bucket_queue_[new_distance_sq].push_back(nloc);
442 bucket_queue_[i].clear();
446void PropagationDistanceField::propagateNegative()
449 for (
unsigned int i = 0; i < negative_bucket_queue_.size(); ++i)
451 EigenSTL::vector_Vector3i::iterator list_it = negative_bucket_queue_[i].begin();
452 EigenSTL::vector_Vector3i::iterator list_end = negative_bucket_queue_[i].end();
453 for (; list_it != list_end; ++list_it)
455 const Eigen::Vector3i& loc = *list_it;
456 PropDistanceFieldVoxel* vptr = &voxel_grid_->getCell(loc.x(), loc.y(), loc.z());
466 if (vptr->negative_update_direction_ < 0 || vptr->negative_update_direction_ > 26)
468 RCLCPP_ERROR(
getLogger(),
"PROGRAMMING ERROR: Invalid update direction detected: %d", vptr->update_direction_);
472 neighborhood = &neighborhoods_[d][vptr->negative_update_direction_];
474 for (
const Eigen::Vector3i& diff : *neighborhood)
476 Eigen::Vector3i nloc(loc.x() + diff.x(), loc.y() + diff.y(), loc.z() + diff.z());
482 PropDistanceFieldVoxel* neighbor = &voxel_grid_->getCell(nloc.x(), nloc.y(), nloc.z());
483 int new_distance_sq = (vptr->closest_negative_point_ - nloc).squaredNorm();
484 if (new_distance_sq > max_distance_sq_)
488 if (new_distance_sq < neighbor->negative_distance_square_)
493 neighbor->negative_distance_square_ = new_distance_sq;
494 neighbor->closest_negative_point_ = vptr->closest_negative_point_;
495 neighbor->negative_update_direction_ = getDirectionNumber(diff.x(), diff.y(), diff.z());
498 negative_bucket_queue_[new_distance_sq].push_back(nloc);
502 negative_bucket_queue_[i].clear();
526void PropagationDistanceField::initNeighborhoods()
529 direction_number_to_direction_.resize(27);
530 for (
int dx = -1; dx <= 1; ++dx)
532 for (
int dy = -1; dy <= 1; ++dy)
534 for (
int dz = -1; dz <= 1; ++dz)
536 int direction_number = getDirectionNumber(dx, dy, dz);
537 Eigen::Vector3i n_point(dx, dy, dz);
538 direction_number_to_direction_[direction_number] = n_point;
543 neighborhoods_.resize(2);
544 for (
int n = 0; n < 2; ++n)
546 neighborhoods_[n].resize(27);
548 for (
int dx = -1; dx <= 1; ++dx)
550 for (
int dy = -1; dy <= 1; ++dy)
552 for (
int dz = -1; dz <= 1; ++dz)
554 int direction_number = getDirectionNumber(dx, dy, dz);
556 for (
int tdx = -1; tdx <= 1; ++tdx)
558 for (
int tdy = -1; tdy <= 1; ++tdy)
560 for (
int tdz = -1; tdz <= 1; ++tdz)
562 if (tdx == 0 && tdy == 0 && tdz == 0)
566 if ((abs(tdx) + abs(tdy) + abs(tdz)) != 1)
568 if (dx * tdx < 0 || dy * tdy < 0 || dz * tdz < 0)
571 Eigen::Vector3i n_point(tdx, tdy, tdz);
572 neighborhoods_[n][direction_number].push_back(n_point);
584int PropagationDistanceField::getDirectionNumber(
int dx,
int dy,
int dz)
const
586 return (dx + 1) * 9 + (dy + 1) * 3 + dz + 1;
589Eigen::Vector3i PropagationDistanceField::getLocationDifference(
int directionNumber)
const
591 return direction_number_to_direction_[directionNumber];
606 return voxel_grid_->isCellValid(x, y, z);
611 return voxel_grid_->getNumCells(
DIM_X);
616 return voxel_grid_->getNumCells(
DIM_Y);
621 return voxel_grid_->getNumCells(
DIM_Z);
626 voxel_grid_->gridToWorld(x, y, z, world_x, world_y, world_z);
632 return voxel_grid_->worldToGrid(world_x, world_y, world_z, x, y, z);
638 os <<
"size_x: " <<
size_x_ <<
'\n';
639 os <<
"size_y: " <<
size_y_ <<
'\n';
640 os <<
"size_z: " <<
size_z_ <<
'\n';
647 boost::iostreams::filtering_ostream out;
648 out.push(boost::iostreams::zlib_compressor());
651 for (
unsigned int x = 0; x < static_cast<unsigned int>(
getXNumCells()); ++x)
653 for (
unsigned int y = 0; y < static_cast<unsigned int>(
getYNumCells()); ++y)
655 for (
unsigned int z = 0; z < static_cast<unsigned int>(
getZNumCells()); z += 8)
657 std::bitset<8> bs(0);
659 for (
unsigned int zi = 0; zi < zv; ++zi)
661 if (
getCell(x, y, z + zi).distance_square_ == 0)
667 out.write(
reinterpret_cast<char*
>(&bs),
sizeof(
char));
683 if (temp !=
"resolution:")
688 if (temp !=
"size_x:")
693 if (temp !=
"size_y:")
698 if (temp !=
"size_z:")
703 if (temp !=
"origin_x:")
708 if (temp !=
"origin_y:")
713 if (temp !=
"origin_z:")
726 boost::iostreams::filtering_istream in;
727 in.push(boost::iostreams::zlib_decompressor());
733 for (
unsigned int x = 0; x < static_cast<unsigned int>(
getXNumCells()); ++x)
735 for (
unsigned int y = 0; y < static_cast<unsigned int>(
getYNumCells()); ++y)
737 for (
unsigned int z = 0; z < static_cast<unsigned int>(
getZNumCells()); z += 8)
745 std::bitset<8> inbit(
static_cast<unsigned long long>(inchar));
747 for (
unsigned int zi = 0; zi < zv; ++zi)
752 obs_points.push_back(Eigen::Vector3i(x, y, z + zi));
758 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...
const PropDistanceFieldVoxel & getCell(int x, int y, int z) const
Gets full cell data given an index.
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.
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
rclcpp::Logger getLogger()
Namespace for holding classes that generate distance fields.
rclcpp::Logger getLogger(const std::string &name)
Creates a namespaced logger.
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.