38 #include <visualization_msgs/Marker.h>
40 #include <boost/iostreams/filtering_stream.hpp>
41 #include <boost/iostreams/copy.hpp>
42 #include <boost/iostreams/filter/zlib.hpp>
47 double origin_x,
double origin_y,
double origin_z,
48 double max_distance,
bool propagate_negative)
49 : DistanceField(size_x, size_y, size_z, resolution, origin_x, origin_y, origin_z)
50 , propagate_negative_(propagate_negative)
51 , max_distance_(max_distance)
58 bool propagate_negative_distances)
59 : DistanceField(bbx_max.
x() - bbx_min.
x(), bbx_max.
y() - bbx_min.
y(), bbx_max.
z() - bbx_min.
z(),
60 octree.getResolution(), bbx_min.
x(), bbx_min.
y(), bbx_min.
z())
61 , propagate_negative_(propagate_negative_distances)
62 , max_distance_(max_distance)
66 addOcTreeToField(&octree);
69 PropagationDistanceField::PropagationDistanceField(std::istream& is,
double max_distance,
70 bool propagate_negative_distances)
71 : DistanceField(0, 0, 0, 0, 0, 0, 0), propagate_negative_(propagate_negative_distances), max_distance_(max_distance)
76 void PropagationDistanceField::initialize()
78 max_distance_sq_ = ceil(max_distance_ / resolution_) * ceil(max_distance_ / resolution_);
80 std::make_shared<VoxelGrid<PropDistanceFieldVoxel>>(size_x_, size_y_, size_z_, resolution_, origin_x_, origin_y_,
85 bucket_queue_.resize(max_distance_sq_ + 1);
86 negative_bucket_queue_.resize(max_distance_sq_ + 1);
89 sqrt_table_.resize(max_distance_sq_ + 1);
90 for (
int i = 0; i <= max_distance_sq_; ++i)
91 sqrt_table_[i] = sqrt(
double(i)) * resolution_;
99 VoxelSet::const_iterator it;
100 for (it =
set.begin(); it !=
set.end(); ++it)
102 Eigen::Vector3i loc1 = *it;
103 ROS_DEBUG_NAMED(
"distance_field",
"%d, %d, %d ", loc1.x(), loc1.y(), loc1.z());
111 EigenSTL::vector_Vector3d::const_iterator it;
112 for (it = points.begin(); it != points.end(); ++it)
115 ROS_DEBUG_NAMED(
"distance_field",
"%g, %g, %g ", loc1.x(), loc1.y(), loc1.z());
117 ROS_DEBUG_NAMED(
"distance_field",
"] size=%u\n", (
unsigned int)points.size());
123 VoxelSet old_point_set;
126 Eigen::Vector3i voxel_loc;
127 bool valid = worldToGrid(old_point.x(), old_point.y(), old_point.z(), voxel_loc.x(), voxel_loc.y(), voxel_loc.z());
130 old_point_set.insert(voxel_loc);
134 VoxelSet new_point_set;
137 Eigen::Vector3i voxel_loc;
138 bool valid = worldToGrid(new_point.x(), new_point.y(), new_point.z(), voxel_loc.x(), voxel_loc.y(), voxel_loc.z());
141 new_point_set.insert(voxel_loc);
144 CompareEigenVector3i comp;
147 std::set_difference(old_point_set.begin(), old_point_set.end(), new_point_set.begin(), new_point_set.end(),
148 std::inserter(old_not_new, old_not_new.end()), comp);
151 std::set_difference(new_point_set.begin(), new_point_set.end(), old_point_set.begin(), old_point_set.end(),
152 std::inserter(new_not_old, new_not_old.end()), comp);
155 for (Eigen::Vector3i& voxel_loc : new_not_old)
157 if (voxel_grid_->getCell(voxel_loc.x(), voxel_loc.y(), voxel_loc.z()).distance_square_ != 0)
159 new_not_in_current.push_back(voxel_loc);
164 removeObstacleVoxels(old_not_new);
165 addNewObstacleVoxels(new_not_in_current);
183 Eigen::Vector3i voxel_loc;
184 bool valid = worldToGrid(
point.x(),
point.y(),
point.z(), voxel_loc.x(), voxel_loc.y(), voxel_loc.z());
188 if (voxel_grid_->getCell(voxel_loc.x(), voxel_loc.y(), voxel_loc.z()).distance_square_ > 0)
190 voxel_points.push_back(voxel_loc);
194 addNewObstacleVoxels(voxel_points);
205 Eigen::Vector3i voxel_loc;
206 bool valid = worldToGrid(
point.x(),
point.y(),
point.z(), voxel_loc.x(), voxel_loc.y(), voxel_loc.z());
210 voxel_points.push_back(voxel_loc);
217 removeObstacleVoxels(voxel_points);
222 int initial_update_direction = getDirectionNumber(0, 0, 0);
223 bucket_queue_[0].reserve(voxel_points.size());
225 if (propagate_negative_)
227 negative_stack.reserve(getXNumCells() * getYNumCells() * getZNumCells());
228 negative_bucket_queue_[0].reserve(voxel_points.size());
231 for (
const Eigen::Vector3i& voxel_point : voxel_points)
234 const Eigen::Vector3i& loc = voxel_point;
238 bucket_queue_[0].push_back(loc);
239 if (propagate_negative_)
245 negative_stack.push_back(loc);
250 if (propagate_negative_)
252 while (!negative_stack.empty())
254 Eigen::Vector3i loc = negative_stack.back();
255 negative_stack.pop_back();
257 for (
int neighbor = 0; neighbor < 27; neighbor++)
259 Eigen::Vector3i diff = getLocationDifference(neighbor);
260 Eigen::Vector3i nloc(loc.x() + diff.x(), loc.y() + diff.y(), loc.z() + diff.z());
262 if (isCellValid(nloc.x(), nloc.y(), nloc.z()))
266 if (!isCellValid(close_point.x(), close_point.y(), close_point.z()))
271 voxel_grid_->getCell(close_point.x(), close_point.y(), close_point.z());
286 negative_stack.push_back(nloc);
293 negative_bucket_queue_[0].push_back(nloc);
307 int initial_update_direction = getDirectionNumber(0, 0, 0);
309 stack.reserve(getXNumCells() * getYNumCells() * getZNumCells());
310 bucket_queue_[0].reserve(voxel_points.size());
311 if (propagate_negative_)
313 negative_stack.reserve(getXNumCells() * getYNumCells() * getZNumCells());
314 negative_bucket_queue_[0].reserve(voxel_points.size());
325 for (
const Eigen::Vector3i& voxel_point : voxel_points)
327 PropDistanceFieldVoxel& voxel = voxel_grid_->getCell(voxel_point.x(), voxel_point.y(), voxel_point.z());
328 voxel.distance_square_ = max_distance_sq_;
329 voxel.closest_point_ = voxel_point;
330 voxel.update_direction_ = initial_update_direction;
331 stack.push_back(voxel_point);
332 if (propagate_negative_)
334 voxel.negative_distance_square_ = 0.0;
335 voxel.closest_negative_point_ = voxel_point;
336 voxel.negative_update_direction_ = initial_update_direction;
337 negative_bucket_queue_[0].push_back(voxel_point);
342 while (!stack.empty())
344 Eigen::Vector3i loc = stack.back();
347 for (
int neighbor = 0; neighbor < 27; neighbor++)
349 Eigen::Vector3i diff = getLocationDifference(neighbor);
350 Eigen::Vector3i nloc(loc.x() + diff.x(), loc.y() + diff.y(), loc.z() + diff.z());
352 if (isCellValid(nloc.x(), nloc.y(), nloc.z()))
354 PropDistanceFieldVoxel& nvoxel = voxel_grid_->getCell(nloc.x(), nloc.y(), nloc.z());
355 Eigen::Vector3i& close_point = nvoxel.closest_point_;
356 if (!isCellValid(close_point.x(), close_point.y(), close_point.z()))
360 PropDistanceFieldVoxel& closest_point_voxel =
361 voxel_grid_->getCell(close_point.x(), close_point.y(), close_point.z());
363 if (closest_point_voxel.distance_square_ != 0)
365 if (nvoxel.distance_square_ != max_distance_sq_)
367 nvoxel.distance_square_ = max_distance_sq_;
368 nvoxel.closest_point_ = nloc;
369 nvoxel.update_direction_ = initial_update_direction;
370 stack.push_back(nloc);
375 nvoxel.update_direction_ = initial_update_direction;
376 bucket_queue_[0].push_back(nloc);
383 if (propagate_negative_)
389 void PropagationDistanceField::propagatePositive()
392 for (
unsigned int i = 0; i < bucket_queue_.size(); ++i)
394 EigenSTL::vector_Vector3i::iterator list_it = bucket_queue_[i].begin();
395 EigenSTL::vector_Vector3i::iterator list_end = bucket_queue_[i].end();
396 for (; list_it != list_end; ++list_it)
398 const Eigen::Vector3i& loc = *list_it;
399 PropDistanceFieldVoxel* vptr = &voxel_grid_->getCell(loc.x(), loc.y(), loc.z());
408 if (vptr->update_direction_ < 0 || vptr->update_direction_ > 26)
410 ROS_ERROR_NAMED(
"distance_field",
"PROGRAMMING ERROR: Invalid update direction detected: %d",
411 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());
420 if (!isCellValid(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_)
438 bucket_queue_[new_distance_sq].push_back(nloc);
442 bucket_queue_[i].clear();
446 void 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 ROS_ERROR_NAMED(
"distance_field",
"PROGRAMMING ERROR: Invalid update direction detected: %d",
469 vptr->update_direction_);
473 neighborhood = &neighborhoods_[
d][vptr->negative_update_direction_];
475 for (
const Eigen::Vector3i& diff : *neighborhood)
477 Eigen::Vector3i nloc(loc.x() + diff.x(), loc.y() + diff.y(), loc.z() + diff.z());
478 if (!isCellValid(nloc.x(), nloc.y(), nloc.z()))
484 int new_distance_sq = (vptr->closest_negative_point_ - nloc).squaredNorm();
485 if (new_distance_sq > max_distance_sq_)
489 if (new_distance_sq < neighbor->negative_distance_square_)
499 negative_bucket_queue_[new_distance_sq].push_back(nloc);
503 negative_bucket_queue_[i].clear();
507 void PropagationDistanceField::reset()
509 voxel_grid_->reset(PropDistanceFieldVoxel(max_distance_sq_, 0));
510 for (
int x = 0;
x < getXNumCells();
x++)
512 for (
int y = 0;
y < getYNumCells();
y++)
514 for (
int z = 0;
z < getZNumCells();
z++)
516 PropDistanceFieldVoxel& voxel = voxel_grid_->getCell(x, y, z);
517 voxel.closest_negative_point_.x() =
x;
518 voxel.closest_negative_point_.y() =
y;
519 voxel.closest_negative_point_.z() =
z;
520 voxel.negative_distance_square_ = 0;
527 void PropagationDistanceField::initNeighborhoods()
530 direction_number_to_direction_.resize(27);
531 for (
int dx = -1; dx <= 1; ++dx)
533 for (
int dy = -1; dy <= 1; ++dy)
535 for (
int dz = -1; dz <= 1; ++dz)
537 int direction_number = getDirectionNumber(dx, dy, dz);
538 Eigen::Vector3i n_point(dx, dy, dz);
539 direction_number_to_direction_[direction_number] = n_point;
544 neighborhoods_.resize(2);
545 for (
int n = 0; n < 2; n++)
547 neighborhoods_[n].resize(27);
549 for (
int dx = -1; dx <= 1; ++dx)
551 for (
int dy = -1; dy <= 1; ++dy)
553 for (
int dz = -1; dz <= 1; ++dz)
555 int direction_number = getDirectionNumber(dx, dy, dz);
557 for (
int tdx = -1; tdx <= 1; ++tdx)
559 for (
int tdy = -1; tdy <= 1; ++tdy)
561 for (
int tdz = -1; tdz <= 1; ++tdz)
563 if (tdx == 0 && tdy == 0 && tdz == 0)
567 if ((abs(tdx) + abs(tdy) + abs(tdz)) != 1)
569 if (dx * tdx < 0 || dy * tdy < 0 || dz * tdz < 0)
572 Eigen::Vector3i n_point(tdx, tdy, tdz);
573 neighborhoods_[n][direction_number].push_back(n_point);
585 int PropagationDistanceField::getDirectionNumber(
int dx,
int dy,
int dz)
const
587 return (dx + 1) * 9 + (dy + 1) * 3 + dz + 1;
590 Eigen::Vector3i PropagationDistanceField::getLocationDifference(
int directionNumber)
const
592 return direction_number_to_direction_[directionNumber];
595 double PropagationDistanceField::getDistance(
double x,
double y,
double z)
const
600 double PropagationDistanceField::getDistance(
int x,
int y,
int z)
const
605 bool PropagationDistanceField::isCellValid(
int x,
int y,
int z)
const
607 return voxel_grid_->isCellValid(x, y, z);
610 int PropagationDistanceField::getXNumCells()
const
612 return voxel_grid_->getNumCells(
DIM_X);
615 int PropagationDistanceField::getYNumCells()
const
617 return voxel_grid_->getNumCells(
DIM_Y);
620 int PropagationDistanceField::getZNumCells()
const
622 return voxel_grid_->getNumCells(
DIM_Z);
625 bool PropagationDistanceField::gridToWorld(
int x,
int y,
int z,
double& world_x,
double& world_y,
double& world_z)
const
627 voxel_grid_->gridToWorld(x, y, z, world_x, world_y, world_z);
631 bool PropagationDistanceField::worldToGrid(
double world_x,
double world_y,
double world_z,
int& x,
int& y,
int& z)
const
633 return voxel_grid_->worldToGrid(world_x, world_y, world_z,
x,
y,
z);
636 bool PropagationDistanceField::writeToStream(std::ostream& os)
const
638 os <<
"resolution: " << resolution_ << std::endl;
639 os <<
"size_x: " << size_x_ << std::endl;
640 os <<
"size_y: " << size_y_ << std::endl;
641 os <<
"size_z: " << size_z_ << std::endl;
642 os <<
"origin_x: " << origin_x_ << std::endl;
643 os <<
"origin_y: " << origin_y_ << std::endl;
644 os <<
"origin_z: " << origin_z_ << std::endl;
648 boost::iostreams::filtering_ostream out;
649 out.push(boost::iostreams::zlib_compressor());
652 for (
unsigned int x = 0; x < static_cast<unsigned int>(getXNumCells());
x++)
654 for (
unsigned int y = 0; y < static_cast<unsigned int>(getYNumCells());
y++)
656 for (
unsigned int z = 0; z < static_cast<unsigned int>(getZNumCells());
z += 8)
658 std::bitset<8> bs(0);
659 unsigned int zv = std::min((
unsigned int)8, getZNumCells() -
z);
660 for (
unsigned int zi = 0; zi < zv; zi++)
662 if (getCell(
x,
y,
z + zi).distance_square_ == 0)
668 out.write((
char*)&bs,
sizeof(
char));
676 bool PropagationDistanceField::readFromStream(std::istream& is)
684 if (temp !=
"resolution:")
689 if (temp !=
"size_x:")
694 if (temp !=
"size_y:")
699 if (temp !=
"size_z:")
704 if (temp !=
"origin_x:")
709 if (temp !=
"origin_y:")
714 if (temp !=
"origin_z:")
727 boost::iostreams::filtering_istream in;
728 in.push(boost::iostreams::zlib_decompressor());
734 for (
unsigned int x = 0; x < static_cast<unsigned int>(getXNumCells());
x++)
736 for (
unsigned int y = 0; y < static_cast<unsigned int>(getYNumCells());
y++)
738 for (
unsigned int z = 0; z < static_cast<unsigned int>(getZNumCells());
z += 8)
746 std::bitset<8> inbit((
unsigned long long)inchar);
747 unsigned int zv = std::min((
unsigned int)8, getZNumCells() - z);
748 for (
unsigned int zi = 0; zi < zv; zi++)
753 obs_points.push_back(Eigen::Vector3i(x, y, z + zi));
759 addNewObstacleVoxels(obs_points);