moveit2
The MoveIt Motion Planning Framework for ROS 2.
propagation_distance_field.cpp
Go to the documentation of this file.
1 /*********************************************************************
2  * Software License Agreement (BSD License)
3  *
4  * Copyright (c) 2009, Willow Garage, Inc.
5  * All rights reserved.
6  *
7  * Redistribution and use in source and binary forms, with or without
8  * modification, are permitted provided that the following conditions
9  * are met:
10  *
11  * * Redistributions of source code must retain the above copyright
12  * notice, this list of conditions and the following disclaimer.
13  * * Redistributions in binary form must reproduce the above
14  * copyright notice, this list of conditions and the following
15  * disclaimer in the documentation and/or other materials provided
16  * with the distribution.
17  * * Neither the name of Willow Garage nor the names of its
18  * contributors may be used to endorse or promote products derived
19  * from this software without specific prior written permission.
20  *
21  * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
22  * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
23  * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
24  * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
25  * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
26  * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
27  * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
28  * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
29  * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
30  * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
31  * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
32  * POSSIBILITY OF SUCH DAMAGE.
33  *********************************************************************/
34 
35 /* Author: Mrinal Kalakrishnan, Ken Anderson */
36 
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>
44 #include <moveit/utils/logger.hpp>
45 
46 namespace distance_field
47 {
48 namespace
49 {
50 rclcpp::Logger getLogger()
51 {
52  return moveit::getLogger("propagation_distance_field");
53 }
54 } // namespace
55 
56 PropagationDistanceField::PropagationDistanceField(double size_x, double size_y, double size_z, double resolution,
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)
62 {
63  initialize();
64 }
65 
66 PropagationDistanceField::PropagationDistanceField(const octomap::OcTree& octree, const octomap::point3d& bbx_min,
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)
73  , max_distance_sq_(0) // avoid gcc warning about uninitialized value
74 {
75  initialize();
76  addOcTreeToField(&octree);
77 }
78 
79 PropagationDistanceField::PropagationDistanceField(std::istream& is, double 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)
82 {
83  readFromStream(is);
84 }
85 
86 void PropagationDistanceField::initialize()
87 {
88  max_distance_sq_ = ceil(max_distance_ / resolution_) * ceil(max_distance_ / resolution_);
89  voxel_grid_ =
90  std::make_shared<VoxelGrid<PropDistanceFieldVoxel>>(size_x_, size_y_, size_z_, resolution_, origin_x_, origin_y_,
91  origin_z_, PropDistanceFieldVoxel(max_distance_sq_, 0));
92 
93  initNeighborhoods();
94 
95  bucket_queue_.resize(max_distance_sq_ + 1);
96  negative_bucket_queue_.resize(max_distance_sq_ + 1);
97 
98  // create a sqrt table:
99  sqrt_table_.resize(max_distance_sq_ + 1);
100  for (int i = 0; i <= max_distance_sq_; ++i)
101  sqrt_table_[i] = sqrt(double(i)) * resolution_;
102 
103  reset();
104 }
105 
106 void PropagationDistanceField::print(const VoxelSet& set)
107 {
108  RCLCPP_DEBUG(getLogger(), "[");
109  VoxelSet::const_iterator it;
110  for (it = set.begin(); it != set.end(); ++it)
111  {
112  Eigen::Vector3i loc1 = *it;
113  RCLCPP_DEBUG(getLogger(), "%d, %d, %d ", loc1.x(), loc1.y(), loc1.z());
114  }
115  RCLCPP_DEBUG(getLogger(), "] size=%u\n", static_cast<unsigned int>(set.size()));
116 }
117 
118 void PropagationDistanceField::print(const EigenSTL::vector_Vector3d& points)
119 {
120  RCLCPP_DEBUG(getLogger(), "[");
121  EigenSTL::vector_Vector3d::const_iterator it;
122  for (it = points.begin(); it != points.end(); ++it)
123  {
124  Eigen::Vector3d loc1 = *it;
125  RCLCPP_DEBUG(getLogger(), "%g, %g, %g ", loc1.x(), loc1.y(), loc1.z());
126  }
127  RCLCPP_DEBUG(getLogger(), "] size=%u\n", static_cast<unsigned int>(points.size()));
128 }
129 
130 void PropagationDistanceField::updatePointsInField(const EigenSTL::vector_Vector3d& old_points,
131  const EigenSTL::vector_Vector3d& new_points)
132 {
133  VoxelSet old_point_set;
134  for (const Eigen::Vector3d& old_point : old_points)
135  {
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());
138  if (valid)
139  {
140  old_point_set.insert(voxel_loc);
141  }
142  }
143 
144  VoxelSet new_point_set;
145  for (const Eigen::Vector3d& new_point : new_points)
146  {
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());
149  if (valid)
150  {
151  new_point_set.insert(voxel_loc);
152  }
153  }
155 
156  EigenSTL::vector_Vector3i old_not_new;
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);
159 
160  EigenSTL::vector_Vector3i new_not_old;
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);
163 
164  EigenSTL::vector_Vector3i new_not_in_current;
165  for (Eigen::Vector3i& voxel_loc : new_not_old)
166  {
167  if (voxel_grid_->getCell(voxel_loc.x(), voxel_loc.y(), voxel_loc.z()).distance_square_ != 0)
168  {
169  new_not_in_current.push_back(voxel_loc);
170  }
171  }
172 
173  removeObstacleVoxels(old_not_new);
174  addNewObstacleVoxels(new_not_in_current);
175 }
176 
177 void PropagationDistanceField::addPointsToField(const EigenSTL::vector_Vector3d& points)
178 {
179  EigenSTL::vector_Vector3i voxel_points;
180 
181  for (const Eigen::Vector3d& point : points)
182  {
183  // Convert to voxel coordinates
184  Eigen::Vector3i voxel_loc;
185  bool valid = worldToGrid(point.x(), point.y(), point.z(), voxel_loc.x(), voxel_loc.y(), voxel_loc.z());
186 
187  if (valid)
188  {
189  if (voxel_grid_->getCell(voxel_loc.x(), voxel_loc.y(), voxel_loc.z()).distance_square_ > 0)
190  {
191  voxel_points.push_back(voxel_loc);
192  }
193  }
194  }
195  addNewObstacleVoxels(voxel_points);
196 }
197 
198 void PropagationDistanceField::removePointsFromField(const EigenSTL::vector_Vector3d& points)
199 {
200  EigenSTL::vector_Vector3i voxel_points;
201  // VoxelSet voxel_locs;
202 
203  for (const Eigen::Vector3d& point : points)
204  {
205  // Convert to voxel coordinates
206  Eigen::Vector3i voxel_loc;
207  bool valid = worldToGrid(point.x(), point.y(), point.z(), voxel_loc.x(), voxel_loc.y(), voxel_loc.z());
208 
209  if (valid)
210  {
211  voxel_points.push_back(voxel_loc);
212  // if(voxel_grid_->getCell(voxel_loc.x(),voxel_loc.y(),voxel_loc.z()).distance_square_ == 0) {
213  // voxel_locs.insert(voxel_loc);
214  //}
215  }
216  }
217 
218  removeObstacleVoxels(voxel_points);
219 }
220 
221 void PropagationDistanceField::addNewObstacleVoxels(const EigenSTL::vector_Vector3i& voxel_points)
222 {
223  int initial_update_direction = getDirectionNumber(0, 0, 0);
224  bucket_queue_[0].reserve(voxel_points.size());
225  EigenSTL::vector_Vector3i negative_stack;
226  if (propagate_negative_)
227  {
228  negative_stack.reserve(getXNumCells() * getYNumCells() * getZNumCells());
229  negative_bucket_queue_[0].reserve(voxel_points.size());
230  }
231 
232  for (const Eigen::Vector3i& voxel_point : voxel_points)
233  {
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_)
241  {
242  voxel.negative_distance_square_ = max_distance_sq_;
243  voxel.closest_negative_point_.x() = PropDistanceFieldVoxel::UNINITIALIZED;
244  voxel.closest_negative_point_.y() = PropDistanceFieldVoxel::UNINITIALIZED;
245  voxel.closest_negative_point_.z() = PropDistanceFieldVoxel::UNINITIALIZED;
246  negative_stack.push_back(loc);
247  }
248  }
249  propagatePositive();
250 
251  if (propagate_negative_)
252  {
253  while (!negative_stack.empty())
254  {
255  Eigen::Vector3i loc = negative_stack.back();
256  negative_stack.pop_back();
257 
258  for (int neighbor = 0; neighbor < 27; ++neighbor)
259  {
260  Eigen::Vector3i diff = getLocationDifference(neighbor);
261  Eigen::Vector3i nloc(loc.x() + diff.x(), loc.y() + diff.y(), loc.z() + diff.z());
262 
263  if (isCellValid(nloc.x(), nloc.y(), nloc.z()))
264  {
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()))
268  {
269  close_point = nloc;
270  }
271  PropDistanceFieldVoxel& closest_point_voxel =
272  voxel_grid_->getCell(close_point.x(), close_point.y(), close_point.z());
273 
274  // our closest non-obstacle cell has become an obstacle
275  if (closest_point_voxel.negative_distance_square_ != 0)
276  {
277  // find all neighbors inside pre-existing obstacles whose
278  // closest_negative_point_ is now an obstacle. These must all be
279  // set to max_distance_sq_ so they will be re-propogated with a new
280  // closest_negative_point_ that is outside the obstacle.
281  if (nvoxel.negative_distance_square_ != max_distance_sq_)
282  {
283  nvoxel.negative_distance_square_ = max_distance_sq_;
284  nvoxel.closest_negative_point_.x() = PropDistanceFieldVoxel::UNINITIALIZED;
285  nvoxel.closest_negative_point_.y() = PropDistanceFieldVoxel::UNINITIALIZED;
286  nvoxel.closest_negative_point_.z() = PropDistanceFieldVoxel::UNINITIALIZED;
287  negative_stack.push_back(nloc);
288  }
289  }
290  else
291  {
292  // this cell still has a valid non-obstacle cell, so we need to propagate from it
293  nvoxel.negative_update_direction_ = initial_update_direction;
294  negative_bucket_queue_[0].push_back(nloc);
295  }
296  }
297  }
298  }
299  propagateNegative();
300  }
301 }
302 
303 void PropagationDistanceField::removeObstacleVoxels(const EigenSTL::vector_Vector3i& voxel_points)
304 // const VoxelSet& locations )
305 {
307  EigenSTL::vector_Vector3i negative_stack;
308  int initial_update_direction = getDirectionNumber(0, 0, 0);
309 
310  stack.reserve(getXNumCells() * getYNumCells() * getZNumCells());
311  bucket_queue_[0].reserve(voxel_points.size());
312  if (propagate_negative_)
313  {
314  negative_stack.reserve(getXNumCells() * getYNumCells() * getZNumCells());
315  negative_bucket_queue_[0].reserve(voxel_points.size());
316  }
317 
318  // First reset the obstacle voxels,
319  // VoxelSet::const_iterator it = locations.begin();
320  // for( it=locations.begin(); it!=locations.end(); ++it)
321  // {
322  // Eigen::Vector3i loc = *it;
323  // bool valid = isCellValid( loc.x(), loc.y(), loc.z());
324  // if (!valid)
325  // continue;
326  for (const Eigen::Vector3i& voxel_point : voxel_points)
327  {
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; // not needed?
332  stack.push_back(voxel_point);
333  if (propagate_negative_)
334  {
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);
339  }
340  }
341 
342  // Reset all neighbors who's closest point is now gone.
343  while (!stack.empty())
344  {
345  Eigen::Vector3i loc = stack.back();
346  stack.pop_back();
347 
348  for (int neighbor = 0; neighbor < 27; ++neighbor)
349  {
350  Eigen::Vector3i diff = getLocationDifference(neighbor);
351  Eigen::Vector3i nloc(loc.x() + diff.x(), loc.y() + diff.y(), loc.z() + diff.z());
352 
353  if (isCellValid(nloc.x(), nloc.y(), nloc.z()))
354  {
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()))
358  {
359  close_point = nloc;
360  }
361  PropDistanceFieldVoxel& closest_point_voxel =
362  voxel_grid_->getCell(close_point.x(), close_point.y(), close_point.z());
363 
364  if (closest_point_voxel.distance_square_ != 0)
365  { // closest point no longer exists
366  if (nvoxel.distance_square_ != max_distance_sq_)
367  {
368  nvoxel.distance_square_ = max_distance_sq_;
369  nvoxel.closest_point_ = nloc;
370  nvoxel.update_direction_ = initial_update_direction; // not needed?
371  stack.push_back(nloc);
372  }
373  }
374  else
375  { // add to queue so we can propagate the values
376  nvoxel.update_direction_ = initial_update_direction;
377  bucket_queue_[0].push_back(nloc);
378  }
379  }
380  }
381  }
382  propagatePositive();
383 
384  if (propagate_negative_)
385  {
386  propagateNegative();
387  }
388 }
389 
390 void PropagationDistanceField::propagatePositive()
391 {
392  // now process the queue:
393  for (unsigned int i = 0; i < bucket_queue_.size(); ++i)
394  {
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)
398  {
399  const Eigen::Vector3i& loc = *list_it;
400  PropDistanceFieldVoxel* vptr = &voxel_grid_->getCell(loc.x(), loc.y(), loc.z());
401 
402  // select the neighborhood list based on the update direction:
403  EigenSTL::vector_Vector3i* neighborhood;
404  int d = i;
405  if (d > 1)
406  d = 1;
407 
408  // This will never happen. update_direction_ is always set before voxel is added to bucket queue.
409  if (vptr->update_direction_ < 0 || vptr->update_direction_ > 26)
410  {
411  RCLCPP_ERROR(getLogger(), "PROGRAMMING ERROR: Invalid update direction detected: %d", vptr->update_direction_);
412  continue;
413  }
414 
415  neighborhood = &neighborhoods_[d][vptr->update_direction_];
416 
417  for (const Eigen::Vector3i& diff : *neighborhood)
418  {
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()))
421  continue;
422 
423  // the real update code:
424  // calculate the neighbor's new distance based on my closest filled voxel:
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_)
428  continue;
429 
430  if (new_distance_sq < neighbor->distance_square_)
431  {
432  // update the neighboring voxel
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());
436 
437  // and put it in the queue:
438  bucket_queue_[new_distance_sq].push_back(nloc);
439  }
440  }
441  }
442  bucket_queue_[i].clear();
443  }
444 }
445 
446 void PropagationDistanceField::propagateNegative()
447 {
448  // now process the queue:
449  for (unsigned int i = 0; i < negative_bucket_queue_.size(); ++i)
450  {
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)
454  {
455  const Eigen::Vector3i& loc = *list_it;
456  PropDistanceFieldVoxel* vptr = &voxel_grid_->getCell(loc.x(), loc.y(), loc.z());
457 
458  // select the neighborhood list based on the update direction:
459  EigenSTL::vector_Vector3i* neighborhood;
460  int d = i;
461  if (d > 1)
462  d = 1;
463 
464  // This will never happen. negative_update_direction_ is always set before voxel is added to
465  // negative_bucket_queue_.
466  if (vptr->negative_update_direction_ < 0 || vptr->negative_update_direction_ > 26)
467  {
468  RCLCPP_ERROR(getLogger(), "PROGRAMMING ERROR: Invalid update direction detected: %d", vptr->update_direction_);
469  continue;
470  }
471 
472  neighborhood = &neighborhoods_[d][vptr->negative_update_direction_];
473 
474  for (const Eigen::Vector3i& diff : *neighborhood)
475  {
476  Eigen::Vector3i nloc(loc.x() + diff.x(), loc.y() + diff.y(), loc.z() + diff.z());
477  if (!isCellValid(nloc.x(), nloc.y(), nloc.z()))
478  continue;
479 
480  // the real update code:
481  // calculate the neighbor's new distance based on my closest filled voxel:
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_)
485  continue;
486  // std::cout << "Looking at " << nloc.x() << " " << nloc.y() << " " << nloc.z() << " " << new_distance_sq << " "
487  // << neighbor->negative_distance_square_ << '\n';
488  if (new_distance_sq < neighbor->negative_distance_square_)
489  {
490  // std::cout << "Updating " << nloc.x() << " " << nloc.y() << " " << nloc.z() << " " << new_distance_sq <<
491  // '\n';
492  // update the neighboring voxel
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());
496 
497  // and put it in the queue:
498  negative_bucket_queue_[new_distance_sq].push_back(nloc);
499  }
500  }
501  }
502  negative_bucket_queue_[i].clear();
503  }
504 }
505 
507 {
508  voxel_grid_->reset(PropDistanceFieldVoxel(max_distance_sq_, 0));
509  for (int x = 0; x < getXNumCells(); ++x)
510  {
511  for (int y = 0; y < getYNumCells(); ++y)
512  {
513  for (int z = 0; z < getZNumCells(); ++z)
514  {
515  PropDistanceFieldVoxel& voxel = voxel_grid_->getCell(x, y, z);
516  voxel.closest_negative_point_.x() = x;
517  voxel.closest_negative_point_.y() = y;
518  voxel.closest_negative_point_.z() = z;
519  voxel.negative_distance_square_ = 0;
520  }
521  }
522  }
523  // object_voxel_locations_.clear();
524 }
525 
526 void PropagationDistanceField::initNeighborhoods()
527 {
528  // first initialize the direction number mapping:
529  direction_number_to_direction_.resize(27);
530  for (int dx = -1; dx <= 1; ++dx)
531  {
532  for (int dy = -1; dy <= 1; ++dy)
533  {
534  for (int dz = -1; dz <= 1; ++dz)
535  {
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;
539  }
540  }
541  }
542 
543  neighborhoods_.resize(2);
544  for (int n = 0; n < 2; ++n)
545  {
546  neighborhoods_[n].resize(27);
547  // source directions
548  for (int dx = -1; dx <= 1; ++dx)
549  {
550  for (int dy = -1; dy <= 1; ++dy)
551  {
552  for (int dz = -1; dz <= 1; ++dz)
553  {
554  int direction_number = getDirectionNumber(dx, dy, dz);
555  // target directions:
556  for (int tdx = -1; tdx <= 1; ++tdx)
557  {
558  for (int tdy = -1; tdy <= 1; ++tdy)
559  {
560  for (int tdz = -1; tdz <= 1; ++tdz)
561  {
562  if (tdx == 0 && tdy == 0 && tdz == 0)
563  continue;
564  if (n >= 1)
565  {
566  if ((abs(tdx) + abs(tdy) + abs(tdz)) != 1)
567  continue;
568  if (dx * tdx < 0 || dy * tdy < 0 || dz * tdz < 0)
569  continue;
570  }
571  Eigen::Vector3i n_point(tdx, tdy, tdz);
572  neighborhoods_[n][direction_number].push_back(n_point);
573  }
574  }
575  }
576  // printf("n=%d, dx=%d, dy=%d, dz=%d, neighbors = %d\n", n, dx, dy, dz,
577  // neighborhoods_[n][direction_number].size());
578  }
579  }
580  }
581  }
582 }
583 
584 int PropagationDistanceField::getDirectionNumber(int dx, int dy, int dz) const
585 {
586  return (dx + 1) * 9 + (dy + 1) * 3 + dz + 1;
587 }
588 
589 Eigen::Vector3i PropagationDistanceField::getLocationDifference(int directionNumber) const
590 {
591  return direction_number_to_direction_[directionNumber];
592 }
593 
594 double PropagationDistanceField::getDistance(double x, double y, double z) const
595 {
596  return getDistance((*voxel_grid_.get())(x, y, z));
597 }
598 
599 double PropagationDistanceField::getDistance(int x, int y, int z) const
600 {
601  return getDistance(voxel_grid_->getCell(x, y, z));
602 }
603 
604 bool PropagationDistanceField::isCellValid(int x, int y, int z) const
605 {
606  return voxel_grid_->isCellValid(x, y, z);
607 }
608 
610 {
611  return voxel_grid_->getNumCells(DIM_X);
612 }
613 
615 {
616  return voxel_grid_->getNumCells(DIM_Y);
617 }
618 
620 {
621  return voxel_grid_->getNumCells(DIM_Z);
622 }
623 
624 bool PropagationDistanceField::gridToWorld(int x, int y, int z, double& world_x, double& world_y, double& world_z) const
625 {
626  voxel_grid_->gridToWorld(x, y, z, world_x, world_y, world_z);
627  return true;
628 }
629 
630 bool PropagationDistanceField::worldToGrid(double world_x, double world_y, double world_z, int& x, int& y, int& z) const
631 {
632  return voxel_grid_->worldToGrid(world_x, world_y, world_z, x, y, z);
633 }
634 
635 bool PropagationDistanceField::writeToStream(std::ostream& os) const
636 {
637  os << "resolution: " << resolution_ << '\n';
638  os << "size_x: " << size_x_ << '\n';
639  os << "size_y: " << size_y_ << '\n';
640  os << "size_z: " << size_z_ << '\n';
641  os << "origin_x: " << origin_x_ << '\n';
642  os << "origin_y: " << origin_y_ << '\n';
643  os << "origin_z: " << origin_z_ << '\n';
644  // now the binary stuff
645 
646  // first writing to zlib compressed buffer
647  boost::iostreams::filtering_ostream out;
648  out.push(boost::iostreams::zlib_compressor());
649  out.push(os);
650 
651  for (unsigned int x = 0; x < static_cast<unsigned int>(getXNumCells()); ++x)
652  {
653  for (unsigned int y = 0; y < static_cast<unsigned int>(getYNumCells()); ++y)
654  {
655  for (unsigned int z = 0; z < static_cast<unsigned int>(getZNumCells()); z += 8)
656  {
657  std::bitset<8> bs(0);
658  unsigned int zv = std::min(8u, getZNumCells() - z);
659  for (unsigned int zi = 0; zi < zv; ++zi)
660  {
661  if (getCell(x, y, z + zi).distance_square_ == 0)
662  {
663  // std::cout << "Marking obs cell " << x << " " << y << " " << z+zi << '\n';
664  bs[zi] = 1;
665  }
666  }
667  out.write(reinterpret_cast<char*>(&bs), sizeof(char));
668  }
669  }
670  }
671  out.flush();
672  return true;
673 }
674 
676 {
677  if (!is.good())
678  return false;
679 
680  std::string temp;
681 
682  is >> temp;
683  if (temp != "resolution:")
684  return false;
685  is >> resolution_;
686 
687  is >> temp;
688  if (temp != "size_x:")
689  return false;
690  is >> size_x_;
691 
692  is >> temp;
693  if (temp != "size_y:")
694  return false;
695  is >> size_y_;
696 
697  is >> temp;
698  if (temp != "size_z:")
699  return false;
700  is >> size_z_;
701 
702  is >> temp;
703  if (temp != "origin_x:")
704  return false;
705  is >> origin_x_;
706 
707  is >> temp;
708  if (temp != "origin_y:")
709  return false;
710  is >> origin_y_;
711 
712  is >> temp;
713  if (temp != "origin_z:")
714  return false;
715  is >> origin_z_;
716 
717  // previous values for propogation_negative_ and max_distance_ will be used
718 
719  initialize();
720 
721  // this should be newline
722  char nl;
723  is.get(nl);
724 
725  // now we start the compressed portion
726  boost::iostreams::filtering_istream in;
727  in.push(boost::iostreams::zlib_decompressor());
728  in.push(is);
729 
730  // std::cout << "Nums " << getXNumCells() << " " << getYNumCells() << " " << getZNumCells() << '\n';
731 
732  EigenSTL::vector_Vector3i obs_points;
733  for (unsigned int x = 0; x < static_cast<unsigned int>(getXNumCells()); ++x)
734  {
735  for (unsigned int y = 0; y < static_cast<unsigned int>(getYNumCells()); ++y)
736  {
737  for (unsigned int z = 0; z < static_cast<unsigned int>(getZNumCells()); z += 8)
738  {
739  char inchar;
740  if (!in.good())
741  {
742  return false;
743  }
744  in.get(inchar);
745  std::bitset<8> inbit(static_cast<unsigned long long>(inchar));
746  unsigned int zv = std::min(8u, getZNumCells() - z);
747  for (unsigned int zi = 0; zi < zv; ++zi)
748  {
749  if (inbit[zi] == 1)
750  {
751  // std::cout << "Adding obs cell " << x << " " << y << " " << z+zi << '\n';
752  obs_points.push_back(Eigen::Vector3i(x, y, z + zi));
753  }
754  }
755  }
756  }
757  }
758  addNewObstacleVoxels(obs_points);
759  return true;
760 }
761 } // namespace distance_field
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
Definition: fcl_compat.h:89
rclcpp::Logger getLogger(const std::string &name)
Creates a namespaced logger.
Definition: logger.cpp:79
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.