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/Marker.h>
39 #include <console_bridge/console.h>
40 #include <boost/iostreams/filtering_stream.hpp>
41 #include <boost/iostreams/copy.hpp>
42 #include <boost/iostreams/filter/zlib.hpp>
43 
44 namespace distance_field
45 {
46 PropagationDistanceField::PropagationDistanceField(double size_x, double size_y, double size_z, double resolution,
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)
52 {
53  initialize();
54 }
55 
57  const octomap::point3d& bbx_max, double 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)
63 {
64  initialize();
65  addOcTreeToField(&octree);
66 }
67 
68 PropagationDistanceField::PropagationDistanceField(std::istream& is, double max_distance,
69  bool propagate_negative_distances)
70  : DistanceField(0, 0, 0, 0, 0, 0, 0), propagate_negative_(propagate_negative_distances), max_distance_(max_distance)
71 {
72  readFromStream(is);
73 }
74 
76 {
80 
82 
83  bucket_queue_.resize(max_distance_sq_ + 1);
85 
86  // create a sqrt table:
87  sqrt_table_.resize(max_distance_sq_ + 1);
88  for (int i = 0; i <= max_distance_sq_; ++i)
89  sqrt_table_[i] = sqrt(double(i)) * resolution_;
90 
91  reset();
92 }
93 
94 int PropagationDistanceField::eucDistSq(Eigen::Vector3i point1, Eigen::Vector3i point2)
95 {
96  int dx = point1.x() - point2.x();
97  int dy = point1.y() - point2.y();
98  int dz = point1.z() - point2.z();
99  return dx * dx + dy * dy + dz * dz;
100 }
101 
103 {
105  VoxelSet::const_iterator it;
106  for (it = set.begin(); it != set.end(); ++it)
107  {
108  Eigen::Vector3i loc1 = *it;
109  CONSOLE_BRIDGE_logDebug("%d, %d, %d ", loc1.x(), loc1.y(), loc1.z());
110  }
111  CONSOLE_BRIDGE_logDebug("] size=%u\n", (unsigned int)set.size());
112 }
113 
115 {
117  EigenSTL::vector_Vector3d::const_iterator it;
118  for (it = points.begin(); it != points.end(); ++it)
119  {
120  Eigen::Vector3d loc1 = *it;
121  CONSOLE_BRIDGE_logDebug("%g, %g, %g ", loc1.x(), loc1.y(), loc1.z());
122  }
123  CONSOLE_BRIDGE_logDebug("] size=%u\n", (unsigned int)points.size());
124 }
125 
127  const EigenSTL::vector_Vector3d& new_points)
128 {
129  VoxelSet old_point_set;
130  for (unsigned int i = 0; i < old_points.size(); i++)
131  {
132  Eigen::Vector3i voxel_loc;
133  bool valid = worldToGrid(old_points[i].x(), old_points[i].y(), old_points[i].z(), voxel_loc.x(), voxel_loc.y(),
134  voxel_loc.z());
135  if (valid)
136  {
137  old_point_set.insert(voxel_loc);
138  }
139  }
140 
141  VoxelSet new_point_set;
142  for (unsigned int i = 0; i < new_points.size(); i++)
143  {
144  Eigen::Vector3i voxel_loc;
145  bool valid = worldToGrid(new_points[i].x(), new_points[i].y(), new_points[i].z(), voxel_loc.x(), voxel_loc.y(),
146  voxel_loc.z());
147  if (valid)
148  {
149  new_point_set.insert(voxel_loc);
150  }
151  }
153 
154  std::vector<Eigen::Vector3i> old_not_new;
155  std::set_difference(old_point_set.begin(), old_point_set.end(), new_point_set.begin(), new_point_set.end(),
156  std::inserter(old_not_new, old_not_new.end()), comp);
157 
158  std::vector<Eigen::Vector3i> new_not_old;
159  std::set_difference(new_point_set.begin(), new_point_set.end(), old_point_set.begin(), old_point_set.end(),
160  std::inserter(new_not_old, new_not_old.end()), comp);
161 
162  std::vector<Eigen::Vector3i> new_not_in_current;
163  for (unsigned int i = 0; i < new_not_old.size(); i++)
164  {
165  if (voxel_grid_->getCell(new_not_old[i].x(), new_not_old[i].y(), new_not_old[i].z()).distance_square_ != 0)
166  {
167  new_not_in_current.push_back(new_not_old[i]);
168  }
169  // CONSOLE_BRIDGE_logInform("Adding obstacle voxel %d %d %d", (*it).x(), (*it).y(), (*it).z());
170  }
171 
172  removeObstacleVoxels(old_not_new);
173  addNewObstacleVoxels(new_not_in_current);
174 
175  // CONSOLE_BRIDGE_logDebug( "new=" );
176  // print(points_added);
177  // CONSOLE_BRIDGE_logDebug( "removed=" );
178  // print(points_removed);
179  // CONSOLE_BRIDGE_logDebug( "obstacle_voxel_locations_=" );
180  // print(object_voxel_locations_);
181  // CONSOLE_BRIDGE_logDebug("");
182 }
183 
185 {
186  std::vector<Eigen::Vector3i> voxel_points;
187 
188  for (unsigned int i = 0; i < points.size(); i++)
189  {
190  // Convert to voxel coordinates
191  Eigen::Vector3i voxel_loc;
192  bool valid = worldToGrid(points[i].x(), points[i].y(), points[i].z(), voxel_loc.x(), voxel_loc.y(), voxel_loc.z());
193 
194  if (valid)
195  {
196  if (voxel_grid_->getCell(voxel_loc.x(), voxel_loc.y(), voxel_loc.z()).distance_square_ > 0)
197  {
198  voxel_points.push_back(voxel_loc);
199  }
200  }
201  }
202  addNewObstacleVoxels(voxel_points);
203 }
204 
206 {
207  std::vector<Eigen::Vector3i> voxel_points;
208  // VoxelSet voxel_locs;
209 
210  for (unsigned int i = 0; i < points.size(); i++)
211  {
212  // Convert to voxel coordinates
213  Eigen::Vector3i voxel_loc;
214  bool valid = worldToGrid(points[i].x(), points[i].y(), points[i].z(), voxel_loc.x(), voxel_loc.y(), voxel_loc.z());
215 
216  if (valid)
217  {
218  voxel_points.push_back(voxel_loc);
219  // if(voxel_grid_->getCell(voxel_loc.x(),voxel_loc.y(),voxel_loc.z()).distance_square_ == 0) {
220  // voxel_locs.insert(voxel_loc);
221  //}
222  }
223  }
224 
225  removeObstacleVoxels(voxel_points);
226 }
227 
228 void PropagationDistanceField::addNewObstacleVoxels(const std::vector<Eigen::Vector3i>& voxel_points)
229 {
230  int initial_update_direction = getDirectionNumber(0, 0, 0);
231  bucket_queue_[0].reserve(voxel_points.size());
232  std::vector<Eigen::Vector3i> negative_stack;
234  {
235  negative_stack.reserve(getXNumCells() * getYNumCells() * getZNumCells());
236  negative_bucket_queue_[0].reserve(voxel_points.size());
237  }
238 
239  for (unsigned int i = 0; i < voxel_points.size(); i++)
240  {
241  PropDistanceFieldVoxel& voxel = voxel_grid_->getCell(voxel_points[i].x(), voxel_points[i].y(), voxel_points[i].z());
242  const Eigen::Vector3i& loc = voxel_points[i];
243  voxel.distance_square_ = 0;
244  voxel.closest_point_ = loc;
245  voxel.update_direction_ = initial_update_direction;
246  bucket_queue_[0].push_back(loc);
248  {
253  negative_stack.push_back(loc);
254  }
255  }
257 
259  {
260  while (!negative_stack.empty())
261  {
262  Eigen::Vector3i loc = negative_stack.back();
263  negative_stack.pop_back();
264 
265  for (int neighbor = 0; neighbor < 27; neighbor++)
266  {
267  Eigen::Vector3i diff = getLocationDifference(neighbor);
268  Eigen::Vector3i nloc(loc.x() + diff.x(), loc.y() + diff.y(), loc.z() + diff.z());
269 
270  if (isCellValid(nloc.x(), nloc.y(), nloc.z()))
271  {
272  PropDistanceFieldVoxel& nvoxel = voxel_grid_->getCell(nloc.x(), nloc.y(), nloc.z());
273  Eigen::Vector3i& close_point = nvoxel.closest_negative_point_;
274  if (!isCellValid(close_point.x(), close_point.y(), close_point.z()))
275  {
276  close_point = nloc;
277  }
278  PropDistanceFieldVoxel& closest_point_voxel =
279  voxel_grid_->getCell(close_point.x(), close_point.y(), close_point.z());
280 
281  // our closest non-obstacle cell has become an obstacle
282  if (closest_point_voxel.negative_distance_square_ != 0)
283  {
284  // find all neigbors inside pre-existing obstacles whose
285  // closest_negative_point_ is now an obstacle. These must all be
286  // set to max_distance_sq_ so they will be re-propogated with a new
287  // closest_negative_point_ that is outside the obstacle.
289  {
294  negative_stack.push_back(nloc);
295  }
296  }
297  else
298  {
299  // this cell still has a valid non-obstacle cell, so we need to propogate from it
300  nvoxel.negative_update_direction_ = initial_update_direction;
301  negative_bucket_queue_[0].push_back(nloc);
302  }
303  }
304  }
305  }
307  }
308 }
309 
310 void PropagationDistanceField::removeObstacleVoxels(const std::vector<Eigen::Vector3i>& voxel_points)
311 // const VoxelSet& locations )
312 {
313  std::vector<Eigen::Vector3i> stack;
314  std::vector<Eigen::Vector3i> negative_stack;
315  int initial_update_direction = getDirectionNumber(0, 0, 0);
316 
317  stack.reserve(getXNumCells() * getYNumCells() * getZNumCells());
318  bucket_queue_[0].reserve(voxel_points.size());
320  {
321  negative_stack.reserve(getXNumCells() * getYNumCells() * getZNumCells());
322  negative_bucket_queue_[0].reserve(voxel_points.size());
323  }
324 
325  // First reset the obstacle voxels,
326  // VoxelSet::const_iterator it = locations.begin();
327  // for( it=locations.begin(); it!=locations.end(); ++it)
328  // {
329  // Eigen::Vector3i loc = *it;
330  // bool valid = isCellValid( loc.x(), loc.y(), loc.z());
331  // if (!valid)
332  // continue;
333  for (unsigned int i = 0; i < voxel_points.size(); i++)
334  {
335  PropDistanceFieldVoxel& voxel = voxel_grid_->getCell(voxel_points[i].x(), voxel_points[i].y(), voxel_points[i].z());
337  voxel.closest_point_ = voxel_points[i];
338  voxel.update_direction_ = initial_update_direction; // not needed?
339  stack.push_back(voxel_points[i]);
341  {
342  voxel.negative_distance_square_ = 0.0;
343  voxel.closest_negative_point_ = voxel_points[i];
344  voxel.negative_update_direction_ = initial_update_direction;
345  negative_bucket_queue_[0].push_back(voxel_points[i]);
346  }
347  }
348 
349  // Reset all neighbors who's closest point is now gone.
350  while (!stack.empty())
351  {
352  Eigen::Vector3i loc = stack.back();
353  stack.pop_back();
354 
355  for (int neighbor = 0; neighbor < 27; neighbor++)
356  {
357  Eigen::Vector3i diff = getLocationDifference(neighbor);
358  Eigen::Vector3i nloc(loc.x() + diff.x(), loc.y() + diff.y(), loc.z() + diff.z());
359 
360  if (isCellValid(nloc.x(), nloc.y(), nloc.z()))
361  {
362  PropDistanceFieldVoxel& nvoxel = voxel_grid_->getCell(nloc.x(), nloc.y(), nloc.z());
363  Eigen::Vector3i& close_point = nvoxel.closest_point_;
364  if (!isCellValid(close_point.x(), close_point.y(), close_point.z()))
365  {
366  close_point = nloc;
367  }
368  PropDistanceFieldVoxel& closest_point_voxel =
369  voxel_grid_->getCell(close_point.x(), close_point.y(), close_point.z());
370 
371  if (closest_point_voxel.distance_square_ != 0)
372  { // closest point no longer exists
373  if (nvoxel.distance_square_ != max_distance_sq_)
374  {
376  nvoxel.closest_point_ = nloc;
377  nvoxel.update_direction_ = initial_update_direction; // not needed?
378  stack.push_back(nloc);
379  }
380  }
381  else
382  { // add to queue so we can propagate the values
383  nvoxel.update_direction_ = initial_update_direction;
384  bucket_queue_[0].push_back(nloc);
385  }
386  }
387  }
388  }
390 
392  {
394  }
395 }
396 
398 {
399  // now process the queue:
400  for (unsigned int i = 0; i < bucket_queue_.size(); ++i)
401  {
402  std::vector<Eigen::Vector3i>::iterator list_it = bucket_queue_[i].begin();
403  std::vector<Eigen::Vector3i>::iterator list_end = bucket_queue_[i].end();
404  for (; list_it != list_end; ++list_it)
405  {
406  const Eigen::Vector3i& loc = *list_it;
407  PropDistanceFieldVoxel* vptr = &voxel_grid_->getCell(loc.x(), loc.y(), loc.z());
408 
409  // select the neighborhood list based on the update direction:
410  std::vector<Eigen::Vector3i>* neighborhood;
411  int D = i;
412  if (D > 1)
413  D = 1;
414 
415  // This will never happen. update_direction_ is always set before voxel is added to bucket queue.
416  if (vptr->update_direction_ < 0 || vptr->update_direction_ > 26)
417  {
418  CONSOLE_BRIDGE_logError("PROGRAMMING ERROR: Invalid update direction detected: %d", vptr->update_direction_);
419  continue;
420  }
421 
422  neighborhood = &neighborhoods_[D][vptr->update_direction_];
423 
424  for (unsigned int n = 0; n < neighborhood->size(); n++)
425  {
426  Eigen::Vector3i diff = (*neighborhood)[n];
427  Eigen::Vector3i nloc(loc.x() + diff.x(), loc.y() + diff.y(), loc.z() + diff.z());
428  if (!isCellValid(nloc.x(), nloc.y(), nloc.z()))
429  continue;
430 
431  // the real update code:
432  // calculate the neighbor's new distance based on my closest filled voxel:
433  PropDistanceFieldVoxel* neighbor = &voxel_grid_->getCell(nloc.x(), nloc.y(), nloc.z());
434  int new_distance_sq = eucDistSq(vptr->closest_point_, nloc);
435  if (new_distance_sq > max_distance_sq_)
436  continue;
437 
438  if (new_distance_sq < neighbor->distance_square_)
439  {
440  // update the neighboring voxel
441  neighbor->distance_square_ = new_distance_sq;
442  neighbor->closest_point_ = vptr->closest_point_;
443  neighbor->update_direction_ = getDirectionNumber(diff.x(), diff.y(), diff.z());
444 
445  // and put it in the queue:
446  bucket_queue_[new_distance_sq].push_back(nloc);
447  }
448  }
449  }
450  bucket_queue_[i].clear();
451  }
452 }
453 
455 {
456  // now process the queue:
457  for (unsigned int i = 0; i < negative_bucket_queue_.size(); ++i)
458  {
459  std::vector<Eigen::Vector3i>::iterator list_it = negative_bucket_queue_[i].begin();
460  std::vector<Eigen::Vector3i>::iterator list_end = negative_bucket_queue_[i].end();
461  for (; list_it != list_end; ++list_it)
462  {
463  const Eigen::Vector3i& loc = *list_it;
464  PropDistanceFieldVoxel* vptr = &voxel_grid_->getCell(loc.x(), loc.y(), loc.z());
465 
466  // select the neighborhood list based on the update direction:
467  std::vector<Eigen::Vector3i>* neighborhood;
468  int D = i;
469  if (D > 1)
470  D = 1;
471 
472  // This will never happen. negative_update_direction_ is always set before voxel is added to
473  // negative_bucket_queue_.
474  if (vptr->negative_update_direction_ < 0 || vptr->negative_update_direction_ > 26)
475  {
476  CONSOLE_BRIDGE_logError("PROGRAMMING ERROR: Invalid update direction detected: %d", vptr->update_direction_);
477  continue;
478  }
479 
480  neighborhood = &neighborhoods_[D][vptr->negative_update_direction_];
481 
482  for (unsigned int n = 0; n < neighborhood->size(); n++)
483  {
484  Eigen::Vector3i diff = (*neighborhood)[n];
485  Eigen::Vector3i nloc(loc.x() + diff.x(), loc.y() + diff.y(), loc.z() + diff.z());
486  if (!isCellValid(nloc.x(), nloc.y(), nloc.z()))
487  continue;
488 
489  // the real update code:
490  // calculate the neighbor's new distance based on my closest filled voxel:
491  PropDistanceFieldVoxel* neighbor = &voxel_grid_->getCell(nloc.x(), nloc.y(), nloc.z());
492  int new_distance_sq = eucDistSq(vptr->closest_negative_point_, nloc);
493  if (new_distance_sq > max_distance_sq_)
494  continue;
495  // std::cout << "Looking at " << nloc.x() << " " << nloc.y() << " " << nloc.z() << " " << new_distance_sq << " "
496  // << neighbor->negative_distance_square_ << std::endl;
497  if (new_distance_sq < neighbor->negative_distance_square_)
498  {
499  // std::cout << "Updating " << nloc.x() << " " << nloc.y() << " " << nloc.z() << " " << new_distance_sq <<
500  // std::endl;
501  // update the neighboring voxel
502  neighbor->negative_distance_square_ = new_distance_sq;
504  neighbor->negative_update_direction_ = getDirectionNumber(diff.x(), diff.y(), diff.z());
505 
506  // and put it in the queue:
507  negative_bucket_queue_[new_distance_sq].push_back(nloc);
508  }
509  }
510  }
511  negative_bucket_queue_[i].clear();
512  }
513 }
514 
516 {
518  for (int x = 0; x < getXNumCells(); x++)
519  {
520  for (int y = 0; y < getYNumCells(); y++)
521  {
522  for (int z = 0; z < getZNumCells(); z++)
523  {
524  PropDistanceFieldVoxel& voxel = voxel_grid_->getCell(x, y, z);
525  voxel.closest_negative_point_.x() = x;
526  voxel.closest_negative_point_.y() = y;
527  voxel.closest_negative_point_.z() = z;
528  voxel.negative_distance_square_ = 0;
529  }
530  }
531  }
532  // object_voxel_locations_.clear();
533 }
534 
536 {
537  // first initialize the direction number mapping:
539  for (int dx = -1; dx <= 1; ++dx)
540  {
541  for (int dy = -1; dy <= 1; ++dy)
542  {
543  for (int dz = -1; dz <= 1; ++dz)
544  {
545  int direction_number = getDirectionNumber(dx, dy, dz);
546  Eigen::Vector3i n_point(dx, dy, dz);
547  direction_number_to_direction_[direction_number] = n_point;
548  }
549  }
550  }
551 
552  neighborhoods_.resize(2);
553  for (int n = 0; n < 2; n++)
554  {
555  neighborhoods_[n].resize(27);
556  // source directions
557  for (int dx = -1; dx <= 1; ++dx)
558  {
559  for (int dy = -1; dy <= 1; ++dy)
560  {
561  for (int dz = -1; dz <= 1; ++dz)
562  {
563  int direction_number = getDirectionNumber(dx, dy, dz);
564  // target directions:
565  for (int tdx = -1; tdx <= 1; ++tdx)
566  {
567  for (int tdy = -1; tdy <= 1; ++tdy)
568  {
569  for (int tdz = -1; tdz <= 1; ++tdz)
570  {
571  if (tdx == 0 && tdy == 0 && tdz == 0)
572  continue;
573  if (n >= 1)
574  {
575  if ((abs(tdx) + abs(tdy) + abs(tdz)) != 1)
576  continue;
577  if (dx * tdx < 0 || dy * tdy < 0 || dz * tdz < 0)
578  continue;
579  }
580  Eigen::Vector3i n_point(tdx, tdy, tdz);
581  neighborhoods_[n][direction_number].push_back(n_point);
582  }
583  }
584  }
585  // printf("n=%d, dx=%d, dy=%d, dz=%d, neighbors = %d\n", n, dx, dy, dz,
586  // neighborhoods_[n][direction_number].size());
587  }
588  }
589  }
590  }
591 }
592 
593 int PropagationDistanceField::getDirectionNumber(int dx, int dy, int dz) const
594 {
595  return (dx + 1) * 9 + (dy + 1) * 3 + dz + 1;
596 }
597 
598 Eigen::Vector3i PropagationDistanceField::getLocationDifference(int directionNumber) const
599 {
600  return direction_number_to_direction_[directionNumber];
601 }
602 
603 double PropagationDistanceField::getDistance(double x, double y, double z) const
604 {
605  return getDistance((*voxel_grid_.get())(x, y, z));
606 }
607 
608 double PropagationDistanceField::getDistance(int x, int y, int z) const
609 {
610  return getDistance(voxel_grid_->getCell(x, y, z));
611 }
612 
613 bool PropagationDistanceField::isCellValid(int x, int y, int z) const
614 {
615  return voxel_grid_->isCellValid(x, y, z);
616 }
617 
619 {
620  return voxel_grid_->getNumCells(DIM_X);
621 }
622 
624 {
625  return voxel_grid_->getNumCells(DIM_Y);
626 }
627 
629 {
630  return voxel_grid_->getNumCells(DIM_Z);
631 }
632 
633 bool PropagationDistanceField::gridToWorld(int x, int y, int z, double& world_x, double& world_y, double& world_z) const
634 {
635  voxel_grid_->gridToWorld(x, y, z, world_x, world_y, world_z);
636  return true;
637 }
638 
639 bool PropagationDistanceField::worldToGrid(double world_x, double world_y, double world_z, int& x, int& y, int& z) const
640 {
641  return voxel_grid_->worldToGrid(world_x, world_y, world_z, x, y, z);
642 }
643 
644 bool PropagationDistanceField::writeToStream(std::ostream& os) const
645 {
646  os << "resolution: " << resolution_ << std::endl;
647  os << "size_x: " << size_x_ << std::endl;
648  os << "size_y: " << size_y_ << std::endl;
649  os << "size_z: " << size_z_ << std::endl;
650  os << "origin_x: " << origin_x_ << std::endl;
651  os << "origin_y: " << origin_y_ << std::endl;
652  os << "origin_z: " << origin_z_ << std::endl;
653  // now the binary stuff
654 
655  // first writing to zlib compressed buffer
656  boost::iostreams::filtering_ostream out;
657  out.push(boost::iostreams::zlib_compressor());
658  out.push(os);
659 
660  for (unsigned int x = 0; x < static_cast<unsigned int>(getXNumCells()); x++)
661  {
662  for (unsigned int y = 0; y < static_cast<unsigned int>(getYNumCells()); y++)
663  {
664  for (unsigned int z = 0; z < static_cast<unsigned int>(getZNumCells()); z += 8)
665  {
666  std::bitset<8> bs(0);
667  unsigned int zv = std::min((unsigned int)8, getZNumCells() - z);
668  for (unsigned int zi = 0; zi < zv; zi++)
669  {
670  if (getCell(x, y, z + zi).distance_square_ == 0)
671  {
672  // std::cout << "Marking obs cell " << x << " " << y << " " << z+zi << std::endl;
673  bs[zi] = 1;
674  }
675  }
676  out.write((char*)&bs, sizeof(char));
677  }
678  }
679  }
680  out.flush();
681  return true;
682 }
683 
685 {
686  if (!is.good())
687  return false;
688 
689  std::string temp;
690 
691  is >> temp;
692  if (temp != "resolution:")
693  return false;
694  is >> resolution_;
695 
696  is >> temp;
697  if (temp != "size_x:")
698  return false;
699  is >> size_x_;
700 
701  is >> temp;
702  if (temp != "size_y:")
703  return false;
704  is >> size_y_;
705 
706  is >> temp;
707  if (temp != "size_z:")
708  return false;
709  is >> size_z_;
710 
711  is >> temp;
712  if (temp != "origin_x:")
713  return false;
714  is >> origin_x_;
715 
716  is >> temp;
717  if (temp != "origin_y:")
718  return false;
719  is >> origin_y_;
720 
721  is >> temp;
722  if (temp != "origin_z:")
723  return false;
724  is >> origin_z_;
725 
726  // previous values for propogation_negative_ and max_distance_ will be used
727 
728  initialize();
729 
730  // this should be newline
731  char nl;
732  is.get(nl);
733 
734  // now we start the compressed portion
735  boost::iostreams::filtering_istream in;
736  in.push(boost::iostreams::zlib_decompressor());
737  in.push(is);
738 
739  // std::cout << "Nums " << getXNumCells() << " " << getYNumCells() << " " << getZNumCells() << std::endl;
740 
741  std::vector<Eigen::Vector3i> obs_points;
742  for (unsigned int x = 0; x < static_cast<unsigned int>(getXNumCells()); x++)
743  {
744  for (unsigned int y = 0; y < static_cast<unsigned int>(getYNumCells()); y++)
745  {
746  for (unsigned int z = 0; z < static_cast<unsigned int>(getZNumCells()); z += 8)
747  {
748  char inchar;
749  if (!in.good())
750  {
751  return false;
752  }
753  in.get(inchar);
754  std::bitset<8> inbit((unsigned long long)inchar);
755  unsigned int zv = std::min((unsigned int)8, getZNumCells() - z);
756  for (unsigned int zi = 0; zi < zv; zi++)
757  {
758  if (inbit[zi] == 1)
759  {
760  // std::cout << "Adding obs cell " << x << " " << y << " " << z+zi << std::endl;
761  obs_points.push_back(Eigen::Vector3i(x, y, z + zi));
762  }
763  }
764  }
765  }
766  }
767  addNewObstacleVoxels(obs_points);
768  return true;
769 }
770 }
virtual void reset()
Resets the entire distance field to max_distance for positive values and zero for negative values...
const PropDistanceFieldVoxel & getCell(int x, int y, int z) const
Gets full cell data given an index.
static const Eigen::Vector3d point2(0.0, 0.1, 0.2)
virtual int getXNumCells() const
Gets the number of cells along the X axis.
bool propagate_negative_
Whether or not to propagate negative distances.
virtual void updatePointsInField(const EigenSTL::vector_Vector3d &old_points, const EigenSTL::vector_Vector3d &new_points)
This function will remove any obstacle points that are in the old point set but not the new point set...
std::set< Eigen::Vector3i, compareEigen_Vector3i > VoxelSet
Typedef for set of integer indices.
std::vector< Eigen::Vector3d, Eigen::aligned_allocator< Eigen::Vector3d > > vector_Vector3d
int distance_square_
Distance in cells to the closest obstacle, squared.
int update_direction_
Direction from which this voxel was updated for occupied distance propagation.
virtual bool writeToStream(std::ostream &stream) const
Writes the contents of the distance field to the supplied stream.
Structure that holds voxel information for the DistanceField. Will be used in VoxelGrid.
double size_x_
X size of the distance field.
IMETHOD Vector diff(const Vector &p_w_a, const Vector &p_w_b, double dt=1)
static const double origin_y
double getResolution() const
Gets the resolution of the distance field in meters.
std::vector< std::vector< Eigen::Vector3i > > negative_bucket_queue_
Data member that holds points from which to propagate in the negative, where each vector holds points...
VoxelGrid holds a dense 3D, axis-aligned set of data at a given resolution, where the data is supplie...
Definition: voxel_grid.h:62
Struct for sorting type Eigen::Vector3i for use in sorted std containers. Sorts in z order...
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...
#define CONSOLE_BRIDGE_logDebug(fmt,...)
Eigen::Vector3i closest_point_
Closest occupied cell.
Eigen::Vector3i closest_negative_point_
Closest unoccupied cell.
static const int UNINITIALIZED
Value that represents an unitialized voxel.
void print(const VoxelSet &set)
Debug function that prints all voxels in a set to CONSOLE_BRIDGE_logDebug.
double y
double origin_y_
Y origin of the distance field.
int getDirectionNumber(int dx, int dy, int dz) const
Helper function to get a single number in a 27 connected 3D voxel grid given dx, dy, and dz values.
DistanceField is an abstract base class for computing distances from sets of 3D obstacle points...
void propagateNegative()
Propagates inward to a maximum distance given the contents of the negative_bucket_queue_, and clears the negative_bucket_queue_.
virtual bool readFromStream(std::istream &stream)
Reads, parameterizes, and populates the distance field based on the supplied stream.
virtual bool worldToGrid(double world_x, double world_y, double world_z, int &x, int &y, int &z) const
Converts from a world location to a set of integer indices. Should return false if the world location...
double size_z_
Z size of the distance field.
static const double resolution
virtual int getYNumCells() const
Gets the number of cells along the Y axis.
static const double origin_z
VoxelGrid< PropDistanceFieldVoxel >::Ptr voxel_grid_
Actual container for distance data.
std::vector< std::vector< Eigen::Vector3i > > bucket_queue_
Structure used to hold propagation frontier.
double z
double origin_z_
Z origin of the distance field.
void addNewObstacleVoxels(const std::vector< Eigen::Vector3i > &voxel_points)
Adds a valid set of integer points to the voxel grid.
INLINE Rall1d< T, V, S > sqrt(const Rall1d< T, V, S > &arg)
void propagatePositive()
Propagates outward to the maximum distance given the contents of the bucket_queue_, and clears the bucket_queue_.
virtual void removePointsFromField(const EigenSTL::vector_Vector3d &points)
Remove a set of obstacle points from the distance field, updating distance values accordingly...
Namespace for holding classes that generate distance fields.
double origin_x_
X origin of the distance field.
#define CONSOLE_BRIDGE_logError(fmt,...)
static const Eigen::Vector3d point1(0.1, 0.0, 0.0)
virtual int getZNumCells() const
Gets the number of cells along the Z axis.
virtual double getDistance(double x, double y, double z) const
Get the distance value associated with the cell indicated by the world coordinate. If the cell is invalid, max_distance will be returned. If running without negative distances, all obstacle cells will have zero distance. If running with negative distances, the distance will be between -max_distance and max_distance, with no values having a 0 distance.
virtual bool isCellValid(int x, int y, int z) const
Determines whether or not the cell associated with the supplied indices is valid for this distance fi...
Eigen::Vector3i getLocationDifference(int directionNumber) const
Helper function that gets change values given single number representing update direction.
INLINE Rall1d< T, V, S > abs(const Rall1d< T, V, S > &x)
void initialize()
Initializes the field, resetting the voxel grid and building a sqrt lookup table for efficiency based...
int negative_distance_square_
Distance in cells to the nearest unoccupied cell, squared.
virtual void addPointsToField(const EigenSTL::vector_Vector3d &points)
Add a set of obstacle points to the distance field, updating distance values accordingly. The distance field may already contain obstacle cells.
std::vector< double > sqrt_table_
Precomputed square root table for faster distance lookups.
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...
std::vector< Eigen::Vector3i > direction_number_to_direction_
Holds conversion from direction number to integer changes.
std::vector< std::vector< std::vector< Eigen::Vector3i > > > neighborhoods_
Holds information on neighbor direction, with 27 different directions. Shows where to propagate given...
void removeObstacleVoxels(const std::vector< Eigen::Vector3i > &voxel_points)
Removes a valid set of integer points from the voxel grid.
static int eucDistSq(Eigen::Vector3i point1, Eigen::Vector3i point2)
Computes squared distance between two 3D integer points.
int negative_update_direction_
Direction from which this voxel was updated for negative distance propagation.
double resolution_
Resolution of the distance field.
double size_y_
Y size of the distance field.
double x
virtual bool gridToWorld(int x, int y, int z, double &world_x, double &world_y, double &world_z) const
Converts from an set of integer indices to a world location given the origin and resolution parameter...
int max_distance_sq_
Holds maximum distance squared in cells.
static const double origin_x
void initNeighborhoods()
Helper function for computing location and neighborhood information in 27 connected voxel grid...


moveit_core
Author(s): Ioan Sucan , Sachin Chitta , Acorn Pooley
autogenerated on Sat Apr 21 2018 02:54:51