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 
45 namespace distance_field
46 {
47 // Logger
48 static const rclcpp::Logger LOGGER = rclcpp::get_logger("moveit_distance_field.propagation_distance_field");
49 
50 PropagationDistanceField::PropagationDistanceField(double size_x, double size_y, double size_z, double resolution,
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)
56 {
57  initialize();
58 }
59 
60 PropagationDistanceField::PropagationDistanceField(const octomap::OcTree& octree, const octomap::point3d& bbx_min,
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)
67  , max_distance_sq_(0) // avoid gcc warning about uninitialized value
68 {
69  initialize();
70  addOcTreeToField(&octree);
71 }
72 
73 PropagationDistanceField::PropagationDistanceField(std::istream& is, double 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)
76 {
77  readFromStream(is);
78 }
79 
80 void PropagationDistanceField::initialize()
81 {
82  max_distance_sq_ = ceil(max_distance_ / resolution_) * ceil(max_distance_ / resolution_);
83  voxel_grid_ =
84  std::make_shared<VoxelGrid<PropDistanceFieldVoxel>>(size_x_, size_y_, size_z_, resolution_, origin_x_, origin_y_,
85  origin_z_, PropDistanceFieldVoxel(max_distance_sq_, 0));
86 
87  initNeighborhoods();
88 
89  bucket_queue_.resize(max_distance_sq_ + 1);
90  negative_bucket_queue_.resize(max_distance_sq_ + 1);
91 
92  // create a sqrt table:
93  sqrt_table_.resize(max_distance_sq_ + 1);
94  for (int i = 0; i <= max_distance_sq_; ++i)
95  sqrt_table_[i] = sqrt(double(i)) * resolution_;
96 
97  reset();
98 }
99 
100 void PropagationDistanceField::print(const VoxelSet& set)
101 {
102  RCLCPP_DEBUG(LOGGER, "[");
103  VoxelSet::const_iterator it;
104  for (it = set.begin(); it != set.end(); ++it)
105  {
106  Eigen::Vector3i loc1 = *it;
107  RCLCPP_DEBUG(LOGGER, "%d, %d, %d ", loc1.x(), loc1.y(), loc1.z());
108  }
109  RCLCPP_DEBUG(LOGGER, "] size=%u\n", (unsigned int)set.size());
110 }
111 
112 void PropagationDistanceField::print(const EigenSTL::vector_Vector3d& points)
113 {
114  RCLCPP_DEBUG(LOGGER, "[");
115  EigenSTL::vector_Vector3d::const_iterator it;
116  for (it = points.begin(); it != points.end(); ++it)
117  {
118  Eigen::Vector3d loc1 = *it;
119  RCLCPP_DEBUG(LOGGER, "%g, %g, %g ", loc1.x(), loc1.y(), loc1.z());
120  }
121  RCLCPP_DEBUG(LOGGER, "] size=%u\n", (unsigned int)points.size());
122 }
123 
124 void PropagationDistanceField::updatePointsInField(const EigenSTL::vector_Vector3d& old_points,
125  const EigenSTL::vector_Vector3d& new_points)
126 {
127  VoxelSet old_point_set;
128  for (const Eigen::Vector3d& old_point : old_points)
129  {
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());
132  if (valid)
133  {
134  old_point_set.insert(voxel_loc);
135  }
136  }
137 
138  VoxelSet new_point_set;
139  for (const Eigen::Vector3d& new_point : new_points)
140  {
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());
143  if (valid)
144  {
145  new_point_set.insert(voxel_loc);
146  }
147  }
149 
150  EigenSTL::vector_Vector3i old_not_new;
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);
153 
154  EigenSTL::vector_Vector3i new_not_old;
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);
157 
158  EigenSTL::vector_Vector3i new_not_in_current;
159  for (Eigen::Vector3i& voxel_loc : new_not_old)
160  {
161  if (voxel_grid_->getCell(voxel_loc.x(), voxel_loc.y(), voxel_loc.z()).distance_square_ != 0)
162  {
163  new_not_in_current.push_back(voxel_loc);
164  }
165  }
166 
167  removeObstacleVoxels(old_not_new);
168  addNewObstacleVoxels(new_not_in_current);
169 }
170 
171 void PropagationDistanceField::addPointsToField(const EigenSTL::vector_Vector3d& points)
172 {
173  EigenSTL::vector_Vector3i voxel_points;
174 
175  for (const Eigen::Vector3d& point : points)
176  {
177  // Convert to voxel coordinates
178  Eigen::Vector3i voxel_loc;
179  bool valid = worldToGrid(point.x(), point.y(), point.z(), voxel_loc.x(), voxel_loc.y(), voxel_loc.z());
180 
181  if (valid)
182  {
183  if (voxel_grid_->getCell(voxel_loc.x(), voxel_loc.y(), voxel_loc.z()).distance_square_ > 0)
184  {
185  voxel_points.push_back(voxel_loc);
186  }
187  }
188  }
189  addNewObstacleVoxels(voxel_points);
190 }
191 
192 void PropagationDistanceField::removePointsFromField(const EigenSTL::vector_Vector3d& points)
193 {
194  EigenSTL::vector_Vector3i voxel_points;
195  // VoxelSet voxel_locs;
196 
197  for (const Eigen::Vector3d& point : points)
198  {
199  // Convert to voxel coordinates
200  Eigen::Vector3i voxel_loc;
201  bool valid = worldToGrid(point.x(), point.y(), point.z(), voxel_loc.x(), voxel_loc.y(), voxel_loc.z());
202 
203  if (valid)
204  {
205  voxel_points.push_back(voxel_loc);
206  // if(voxel_grid_->getCell(voxel_loc.x(),voxel_loc.y(),voxel_loc.z()).distance_square_ == 0) {
207  // voxel_locs.insert(voxel_loc);
208  //}
209  }
210  }
211 
212  removeObstacleVoxels(voxel_points);
213 }
214 
215 void PropagationDistanceField::addNewObstacleVoxels(const EigenSTL::vector_Vector3i& voxel_points)
216 {
217  int initial_update_direction = getDirectionNumber(0, 0, 0);
218  bucket_queue_[0].reserve(voxel_points.size());
219  EigenSTL::vector_Vector3i negative_stack;
220  if (propagate_negative_)
221  {
222  negative_stack.reserve(getXNumCells() * getYNumCells() * getZNumCells());
223  negative_bucket_queue_[0].reserve(voxel_points.size());
224  }
225 
226  for (const Eigen::Vector3i& voxel_point : voxel_points)
227  {
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_)
235  {
236  voxel.negative_distance_square_ = max_distance_sq_;
237  voxel.closest_negative_point_.x() = PropDistanceFieldVoxel::UNINITIALIZED;
238  voxel.closest_negative_point_.y() = PropDistanceFieldVoxel::UNINITIALIZED;
239  voxel.closest_negative_point_.z() = PropDistanceFieldVoxel::UNINITIALIZED;
240  negative_stack.push_back(loc);
241  }
242  }
243  propagatePositive();
244 
245  if (propagate_negative_)
246  {
247  while (!negative_stack.empty())
248  {
249  Eigen::Vector3i loc = negative_stack.back();
250  negative_stack.pop_back();
251 
252  for (int neighbor = 0; neighbor < 27; ++neighbor)
253  {
254  Eigen::Vector3i diff = getLocationDifference(neighbor);
255  Eigen::Vector3i nloc(loc.x() + diff.x(), loc.y() + diff.y(), loc.z() + diff.z());
256 
257  if (isCellValid(nloc.x(), nloc.y(), nloc.z()))
258  {
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()))
262  {
263  close_point = nloc;
264  }
265  PropDistanceFieldVoxel& closest_point_voxel =
266  voxel_grid_->getCell(close_point.x(), close_point.y(), close_point.z());
267 
268  // our closest non-obstacle cell has become an obstacle
269  if (closest_point_voxel.negative_distance_square_ != 0)
270  {
271  // find all neighbors inside pre-existing obstacles whose
272  // closest_negative_point_ is now an obstacle. These must all be
273  // set to max_distance_sq_ so they will be re-propogated with a new
274  // closest_negative_point_ that is outside the obstacle.
275  if (nvoxel.negative_distance_square_ != max_distance_sq_)
276  {
277  nvoxel.negative_distance_square_ = max_distance_sq_;
278  nvoxel.closest_negative_point_.x() = PropDistanceFieldVoxel::UNINITIALIZED;
279  nvoxel.closest_negative_point_.y() = PropDistanceFieldVoxel::UNINITIALIZED;
280  nvoxel.closest_negative_point_.z() = PropDistanceFieldVoxel::UNINITIALIZED;
281  negative_stack.push_back(nloc);
282  }
283  }
284  else
285  {
286  // this cell still has a valid non-obstacle cell, so we need to propagate from it
287  nvoxel.negative_update_direction_ = initial_update_direction;
288  negative_bucket_queue_[0].push_back(nloc);
289  }
290  }
291  }
292  }
293  propagateNegative();
294  }
295 }
296 
297 void PropagationDistanceField::removeObstacleVoxels(const EigenSTL::vector_Vector3i& voxel_points)
298 // const VoxelSet& locations )
299 {
301  EigenSTL::vector_Vector3i negative_stack;
302  int initial_update_direction = getDirectionNumber(0, 0, 0);
303 
304  stack.reserve(getXNumCells() * getYNumCells() * getZNumCells());
305  bucket_queue_[0].reserve(voxel_points.size());
306  if (propagate_negative_)
307  {
308  negative_stack.reserve(getXNumCells() * getYNumCells() * getZNumCells());
309  negative_bucket_queue_[0].reserve(voxel_points.size());
310  }
311 
312  // First reset the obstacle voxels,
313  // VoxelSet::const_iterator it = locations.begin();
314  // for( it=locations.begin(); it!=locations.end(); ++it)
315  // {
316  // Eigen::Vector3i loc = *it;
317  // bool valid = isCellValid( loc.x(), loc.y(), loc.z());
318  // if (!valid)
319  // continue;
320  for (const Eigen::Vector3i& voxel_point : voxel_points)
321  {
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; // not needed?
326  stack.push_back(voxel_point);
327  if (propagate_negative_)
328  {
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);
333  }
334  }
335 
336  // Reset all neighbors who's closest point is now gone.
337  while (!stack.empty())
338  {
339  Eigen::Vector3i loc = stack.back();
340  stack.pop_back();
341 
342  for (int neighbor = 0; neighbor < 27; ++neighbor)
343  {
344  Eigen::Vector3i diff = getLocationDifference(neighbor);
345  Eigen::Vector3i nloc(loc.x() + diff.x(), loc.y() + diff.y(), loc.z() + diff.z());
346 
347  if (isCellValid(nloc.x(), nloc.y(), nloc.z()))
348  {
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()))
352  {
353  close_point = nloc;
354  }
355  PropDistanceFieldVoxel& closest_point_voxel =
356  voxel_grid_->getCell(close_point.x(), close_point.y(), close_point.z());
357 
358  if (closest_point_voxel.distance_square_ != 0)
359  { // closest point no longer exists
360  if (nvoxel.distance_square_ != max_distance_sq_)
361  {
362  nvoxel.distance_square_ = max_distance_sq_;
363  nvoxel.closest_point_ = nloc;
364  nvoxel.update_direction_ = initial_update_direction; // not needed?
365  stack.push_back(nloc);
366  }
367  }
368  else
369  { // add to queue so we can propagate the values
370  nvoxel.update_direction_ = initial_update_direction;
371  bucket_queue_[0].push_back(nloc);
372  }
373  }
374  }
375  }
376  propagatePositive();
377 
378  if (propagate_negative_)
379  {
380  propagateNegative();
381  }
382 }
383 
384 void PropagationDistanceField::propagatePositive()
385 {
386  // now process the queue:
387  for (unsigned int i = 0; i < bucket_queue_.size(); ++i)
388  {
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)
392  {
393  const Eigen::Vector3i& loc = *list_it;
394  PropDistanceFieldVoxel* vptr = &voxel_grid_->getCell(loc.x(), loc.y(), loc.z());
395 
396  // select the neighborhood list based on the update direction:
397  EigenSTL::vector_Vector3i* neighborhood;
398  int d = i;
399  if (d > 1)
400  d = 1;
401 
402  // This will never happen. update_direction_ is always set before voxel is added to bucket queue.
403  if (vptr->update_direction_ < 0 || vptr->update_direction_ > 26)
404  {
405  RCLCPP_ERROR(LOGGER, "PROGRAMMING ERROR: Invalid update direction detected: %d", vptr->update_direction_);
406  continue;
407  }
408 
409  neighborhood = &neighborhoods_[d][vptr->update_direction_];
410 
411  for (const Eigen::Vector3i& diff : *neighborhood)
412  {
413  Eigen::Vector3i nloc(loc.x() + diff.x(), loc.y() + diff.y(), loc.z() + diff.z());
414  if (!isCellValid(nloc.x(), nloc.y(), nloc.z()))
415  continue;
416 
417  // the real update code:
418  // calculate the neighbor's new distance based on my closest filled voxel:
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_)
422  continue;
423 
424  if (new_distance_sq < neighbor->distance_square_)
425  {
426  // update the neighboring voxel
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());
430 
431  // and put it in the queue:
432  bucket_queue_[new_distance_sq].push_back(nloc);
433  }
434  }
435  }
436  bucket_queue_[i].clear();
437  }
438 }
439 
440 void PropagationDistanceField::propagateNegative()
441 {
442  // now process the queue:
443  for (unsigned int i = 0; i < negative_bucket_queue_.size(); ++i)
444  {
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)
448  {
449  const Eigen::Vector3i& loc = *list_it;
450  PropDistanceFieldVoxel* vptr = &voxel_grid_->getCell(loc.x(), loc.y(), loc.z());
451 
452  // select the neighborhood list based on the update direction:
453  EigenSTL::vector_Vector3i* neighborhood;
454  int d = i;
455  if (d > 1)
456  d = 1;
457 
458  // This will never happen. negative_update_direction_ is always set before voxel is added to
459  // negative_bucket_queue_.
460  if (vptr->negative_update_direction_ < 0 || vptr->negative_update_direction_ > 26)
461  {
462  RCLCPP_ERROR(LOGGER, "PROGRAMMING ERROR: Invalid update direction detected: %d", vptr->update_direction_);
463  continue;
464  }
465 
466  neighborhood = &neighborhoods_[d][vptr->negative_update_direction_];
467 
468  for (const Eigen::Vector3i& diff : *neighborhood)
469  {
470  Eigen::Vector3i nloc(loc.x() + diff.x(), loc.y() + diff.y(), loc.z() + diff.z());
471  if (!isCellValid(nloc.x(), nloc.y(), nloc.z()))
472  continue;
473 
474  // the real update code:
475  // calculate the neighbor's new distance based on my closest filled voxel:
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_)
479  continue;
480  // std::cout << "Looking at " << nloc.x() << " " << nloc.y() << " " << nloc.z() << " " << new_distance_sq << " "
481  // << neighbor->negative_distance_square_ << '\n';
482  if (new_distance_sq < neighbor->negative_distance_square_)
483  {
484  // std::cout << "Updating " << nloc.x() << " " << nloc.y() << " " << nloc.z() << " " << new_distance_sq <<
485  // '\n';
486  // update the neighboring voxel
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());
490 
491  // and put it in the queue:
492  negative_bucket_queue_[new_distance_sq].push_back(nloc);
493  }
494  }
495  }
496  negative_bucket_queue_[i].clear();
497  }
498 }
499 
501 {
502  voxel_grid_->reset(PropDistanceFieldVoxel(max_distance_sq_, 0));
503  for (int x = 0; x < getXNumCells(); ++x)
504  {
505  for (int y = 0; y < getYNumCells(); ++y)
506  {
507  for (int z = 0; z < getZNumCells(); ++z)
508  {
509  PropDistanceFieldVoxel& voxel = voxel_grid_->getCell(x, y, z);
510  voxel.closest_negative_point_.x() = x;
511  voxel.closest_negative_point_.y() = y;
512  voxel.closest_negative_point_.z() = z;
513  voxel.negative_distance_square_ = 0;
514  }
515  }
516  }
517  // object_voxel_locations_.clear();
518 }
519 
520 void PropagationDistanceField::initNeighborhoods()
521 {
522  // first initialize the direction number mapping:
523  direction_number_to_direction_.resize(27);
524  for (int dx = -1; dx <= 1; ++dx)
525  {
526  for (int dy = -1; dy <= 1; ++dy)
527  {
528  for (int dz = -1; dz <= 1; ++dz)
529  {
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;
533  }
534  }
535  }
536 
537  neighborhoods_.resize(2);
538  for (int n = 0; n < 2; ++n)
539  {
540  neighborhoods_[n].resize(27);
541  // source directions
542  for (int dx = -1; dx <= 1; ++dx)
543  {
544  for (int dy = -1; dy <= 1; ++dy)
545  {
546  for (int dz = -1; dz <= 1; ++dz)
547  {
548  int direction_number = getDirectionNumber(dx, dy, dz);
549  // target directions:
550  for (int tdx = -1; tdx <= 1; ++tdx)
551  {
552  for (int tdy = -1; tdy <= 1; ++tdy)
553  {
554  for (int tdz = -1; tdz <= 1; ++tdz)
555  {
556  if (tdx == 0 && tdy == 0 && tdz == 0)
557  continue;
558  if (n >= 1)
559  {
560  if ((abs(tdx) + abs(tdy) + abs(tdz)) != 1)
561  continue;
562  if (dx * tdx < 0 || dy * tdy < 0 || dz * tdz < 0)
563  continue;
564  }
565  Eigen::Vector3i n_point(tdx, tdy, tdz);
566  neighborhoods_[n][direction_number].push_back(n_point);
567  }
568  }
569  }
570  // printf("n=%d, dx=%d, dy=%d, dz=%d, neighbors = %d\n", n, dx, dy, dz,
571  // neighborhoods_[n][direction_number].size());
572  }
573  }
574  }
575  }
576 }
577 
578 int PropagationDistanceField::getDirectionNumber(int dx, int dy, int dz) const
579 {
580  return (dx + 1) * 9 + (dy + 1) * 3 + dz + 1;
581 }
582 
583 Eigen::Vector3i PropagationDistanceField::getLocationDifference(int directionNumber) const
584 {
585  return direction_number_to_direction_[directionNumber];
586 }
587 
588 double PropagationDistanceField::getDistance(double x, double y, double z) const
589 {
590  return getDistance((*voxel_grid_.get())(x, y, z));
591 }
592 
593 double PropagationDistanceField::getDistance(int x, int y, int z) const
594 {
595  return getDistance(voxel_grid_->getCell(x, y, z));
596 }
597 
598 bool PropagationDistanceField::isCellValid(int x, int y, int z) const
599 {
600  return voxel_grid_->isCellValid(x, y, z);
601 }
602 
604 {
605  return voxel_grid_->getNumCells(DIM_X);
606 }
607 
609 {
610  return voxel_grid_->getNumCells(DIM_Y);
611 }
612 
614 {
615  return voxel_grid_->getNumCells(DIM_Z);
616 }
617 
618 bool PropagationDistanceField::gridToWorld(int x, int y, int z, double& world_x, double& world_y, double& world_z) const
619 {
620  voxel_grid_->gridToWorld(x, y, z, world_x, world_y, world_z);
621  return true;
622 }
623 
624 bool PropagationDistanceField::worldToGrid(double world_x, double world_y, double world_z, int& x, int& y, int& z) const
625 {
626  return voxel_grid_->worldToGrid(world_x, world_y, world_z, x, y, z);
627 }
628 
629 bool PropagationDistanceField::writeToStream(std::ostream& os) const
630 {
631  os << "resolution: " << resolution_ << '\n';
632  os << "size_x: " << size_x_ << '\n';
633  os << "size_y: " << size_y_ << '\n';
634  os << "size_z: " << size_z_ << '\n';
635  os << "origin_x: " << origin_x_ << '\n';
636  os << "origin_y: " << origin_y_ << '\n';
637  os << "origin_z: " << origin_z_ << '\n';
638  // now the binary stuff
639 
640  // first writing to zlib compressed buffer
641  boost::iostreams::filtering_ostream out;
642  out.push(boost::iostreams::zlib_compressor());
643  out.push(os);
644 
645  for (unsigned int x = 0; x < static_cast<unsigned int>(getXNumCells()); ++x)
646  {
647  for (unsigned int y = 0; y < static_cast<unsigned int>(getYNumCells()); ++y)
648  {
649  for (unsigned int z = 0; z < static_cast<unsigned int>(getZNumCells()); z += 8)
650  {
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)
654  {
655  if (getCell(x, y, z + zi).distance_square_ == 0)
656  {
657  // std::cout << "Marking obs cell " << x << " " << y << " " << z+zi << '\n';
658  bs[zi] = 1;
659  }
660  }
661  out.write((char*)&bs, sizeof(char));
662  }
663  }
664  }
665  out.flush();
666  return true;
667 }
668 
670 {
671  if (!is.good())
672  return false;
673 
674  std::string temp;
675 
676  is >> temp;
677  if (temp != "resolution:")
678  return false;
679  is >> resolution_;
680 
681  is >> temp;
682  if (temp != "size_x:")
683  return false;
684  is >> size_x_;
685 
686  is >> temp;
687  if (temp != "size_y:")
688  return false;
689  is >> size_y_;
690 
691  is >> temp;
692  if (temp != "size_z:")
693  return false;
694  is >> size_z_;
695 
696  is >> temp;
697  if (temp != "origin_x:")
698  return false;
699  is >> origin_x_;
700 
701  is >> temp;
702  if (temp != "origin_y:")
703  return false;
704  is >> origin_y_;
705 
706  is >> temp;
707  if (temp != "origin_z:")
708  return false;
709  is >> origin_z_;
710 
711  // previous values for propogation_negative_ and max_distance_ will be used
712 
713  initialize();
714 
715  // this should be newline
716  char nl;
717  is.get(nl);
718 
719  // now we start the compressed portion
720  boost::iostreams::filtering_istream in;
721  in.push(boost::iostreams::zlib_decompressor());
722  in.push(is);
723 
724  // std::cout << "Nums " << getXNumCells() << " " << getYNumCells() << " " << getZNumCells() << '\n';
725 
726  EigenSTL::vector_Vector3i obs_points;
727  for (unsigned int x = 0; x < static_cast<unsigned int>(getXNumCells()); ++x)
728  {
729  for (unsigned int y = 0; y < static_cast<unsigned int>(getYNumCells()); ++y)
730  {
731  for (unsigned int z = 0; z < static_cast<unsigned int>(getZNumCells()); z += 8)
732  {
733  char inchar;
734  if (!in.good())
735  {
736  return false;
737  }
738  in.get(inchar);
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)
742  {
743  if (inbit[zi] == 1)
744  {
745  // std::cout << "Adding obs cell " << x << " " << y << " " << z+zi << '\n';
746  obs_points.push_back(Eigen::Vector3i(x, y, z + zi));
747  }
748  }
749  }
750  }
751  }
752  addNewObstacleVoxels(obs_points);
753  return true;
754 }
755 } // 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
x
Definition: pick.py:64
y
Definition: pick.py:65
z
Definition: pick.py:66
d
Definition: setup.py:4
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.