costmap_to_polygons.cpp
Go to the documentation of this file.
1 /*********************************************************************
2  *
3  * Software License Agreement (BSD License)
4  *
5  * Copyright (c) 2016,
6  * TU Dortmund - Institute of Control Theory and Systems Engineering.
7  * All rights reserved.
8  *
9  * Redistribution and use in source and binary forms, with or without
10  * modification, are permitted provided that the following conditions
11  * are met:
12  *
13  * * Redistributions of source code must retain the above copyright
14  * notice, this list of conditions and the following disclaimer.
15  * * Redistributions in binary form must reproduce the above
16  * copyright notice, this list of conditions and the following
17  * disclaimer in the documentation and/or other materials provided
18  * with the distribution.
19  * * Neither the name of the institute nor the names of its
20  * contributors may be used to endorse or promote products derived
21  * from this software without specific prior written permission.
22  *
23  * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
24  * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
25  * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
26  * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
27  * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
28  * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
29  * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
30  * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
31  * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
32  * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
33  * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
34  * POSSIBILITY OF SUCH DAMAGE.
35  *
36  * Author: Christoph Rösmann, Otniel Rinaldo
37  *********************************************************************/
38 
40 #include <costmap_converter/misc.h>
41 #include <boost/thread.hpp>
42 #include <boost/thread/mutex.hpp>
44 
46 
47 namespace
48 {
49 
60 std::vector<geometry_msgs::Point32> douglasPeucker(std::vector<geometry_msgs::Point32>::iterator begin,
61  std::vector<geometry_msgs::Point32>::iterator end, double epsilon)
62 {
63  if (std::distance(begin, end) <= 2)
64  {
65  return std::vector<geometry_msgs::Point32>(begin, end);
66  }
67 
68  // Find the point with the maximum distance from the line [begin, end)
69  double dmax = std::numeric_limits<double>::lowest();
70  std::vector<geometry_msgs::Point32>::iterator max_dist_it;
71  std::vector<geometry_msgs::Point32>::iterator last = std::prev(end);
72  for (auto it = std::next(begin); it != last; ++it)
73  {
74  double d = costmap_converter::computeSquaredDistanceToLineSegment(*it, *begin, *last);
75  if (d > dmax)
76  {
77  max_dist_it = it;
78  dmax = d;
79  }
80  }
81 
82  if (dmax < epsilon * epsilon)
83  { // termination criterion reached, line is good enough
84  std::vector<geometry_msgs::Point32> result;
85  result.push_back(*begin);
86  result.push_back(*last);
87  return result;
88  }
89 
90  // Recursive calls for the two splitted parts
91  auto firstLineSimplified = douglasPeucker(begin, std::next(max_dist_it), epsilon);
92  auto secondLineSimplified = douglasPeucker(max_dist_it, end, epsilon);
93 
94  // Combine the two lines into one line and return the merged line.
95  // Note that we have to skip the first point of the second line, as it is duplicated above.
96  firstLineSimplified.insert(firstLineSimplified.end(),
97  std::make_move_iterator(std::next(secondLineSimplified.begin())),
98  std::make_move_iterator(secondLineSimplified.end()));
99  return firstLineSimplified;
100 }
101 
102 } // end namespace
103 
104 namespace costmap_converter
105 {
106 
108 {
109  costmap_ = NULL;
110  dynamic_recfg_ = NULL;
112  offset_x_ = offset_y_ = 0.;
113 }
114 
116 {
117  if (dynamic_recfg_ != NULL)
118  delete dynamic_recfg_;
119 }
120 
122 {
123  costmap_ = NULL;
124 
125  nh.param("cluster_max_distance", parameter_.max_distance_, 0.4);
126  nh.param("cluster_min_pts", parameter_.min_pts_, 2);
127  nh.param("cluster_max_pts", parameter_.max_pts_, 30);
128  nh.param("convex_hull_min_pt_separation", parameter_.min_keypoint_separation_, 0.1);
129 
131 
132  // setup dynamic reconfigure
133  dynamic_recfg_ = new dynamic_reconfigure::Server<CostmapToPolygonsDBSMCCHConfig>(nh);
134  dynamic_reconfigure::Server<CostmapToPolygonsDBSMCCHConfig>::CallbackType cb = boost::bind(&CostmapToPolygonsDBSMCCH::reconfigureCB, this, _1, _2);
135  dynamic_recfg_->setCallback(cb);
136 }
137 
138 
140 {
141  std::vector< std::vector<KeyPoint> > clusters;
142  dbScan(clusters);
143 
144  // Create new polygon container
145  PolygonContainerPtr polygons(new std::vector<geometry_msgs::Polygon>());
146 
147 
148  // add convex hulls to polygon container
149  for (std::size_t i = 1; i <clusters.size(); ++i) // skip first cluster, since it is just noise
150  {
151  polygons->push_back( geometry_msgs::Polygon() );
152  convexHull2(clusters[i], polygons->back() );
153  }
154 
155  // add our non-cluster points to the polygon container (as single points)
156  if (!clusters.empty())
157  {
158  for (std::size_t i=0; i < clusters.front().size(); ++i)
159  {
160  polygons->push_back( geometry_msgs::Polygon() );
161  convertPointToPolygon(clusters.front()[i], polygons->back());
162  }
163  }
164 
165  // replace shared polygon container
166  updatePolygonContainer(polygons);
167 }
168 
170 {
171  if (!costmap)
172  return;
173 
174  costmap_ = costmap;
175 
176  updateCostmap2D();
177 }
178 
180 {
181  occupied_cells_.clear();
182 
183  if (!costmap_->getMutex())
184  {
185  ROS_ERROR("Cannot update costmap since the mutex pointer is null");
186  return;
187  }
188 
189  { // get a copy of our parameters from dynamic reconfigure
190  boost::mutex::scoped_lock lock(parameter_mutex_);
192  }
193 
194  costmap_2d::Costmap2D::mutex_t::scoped_lock lock(*costmap_->getMutex());
195 
196  // allocate neighbor lookup
197  int cells_x = int(costmap_->getSizeInMetersX() / parameter_.max_distance_) + 1;
198  int cells_y = int(costmap_->getSizeInMetersY() / parameter_.max_distance_) + 1;
199 
200  if (cells_x != neighbor_size_x_ || cells_y != neighbor_size_y_) {
201  neighbor_size_x_ = cells_x;
202  neighbor_size_y_ = cells_y;
204  }
207  for (auto& n : neighbor_lookup_)
208  n.clear();
209 
210  // get indices of obstacle cells
211  for(std::size_t i = 0; i < costmap_->getSizeInCellsX(); i++)
212  {
213  for(std::size_t j = 0; j < costmap_->getSizeInCellsY(); j++)
214  {
215  int value = costmap_->getCost(i,j);
216  if(value >= costmap_2d::LETHAL_OBSTACLE)
217  {
218  double x, y;
219  costmap_->mapToWorld((unsigned int)i, (unsigned int)j, x, y);
220  addPoint(x, y);
221  }
222  }
223  }
224 }
225 
226 
227 void CostmapToPolygonsDBSMCCH::dbScan(std::vector< std::vector<KeyPoint> >& clusters)
228 {
229  std::vector<bool> visited(occupied_cells_.size(), false);
230 
231  clusters.clear();
232 
233  //DB Scan Algorithm
234  int cluster_id = 0; // current cluster_id
235  clusters.push_back(std::vector<KeyPoint>());
236  for(int i = 0; i< (int)occupied_cells_.size(); i++)
237  {
238  if(!visited[i]) //keypoint has not been visited before
239  {
240  visited[i] = true; // mark as visited
241  std::vector<int> neighbors;
242  regionQuery(i, neighbors); //Find neighbors around the keypoint
243  if((int)neighbors.size() < parameter_.min_pts_) //If not enough neighbors are found, mark as noise
244  {
245  clusters[0].push_back(occupied_cells_[i]);
246  }
247  else
248  {
249  ++cluster_id; // increment current cluster_id
250  clusters.push_back(std::vector<KeyPoint>());
251 
252  // Expand the cluster
253  clusters[cluster_id].push_back(occupied_cells_[i]);
254  for(int j = 0; j<(int)neighbors.size(); j++)
255  {
256  if ((int)clusters[cluster_id].size() == parameter_.max_pts_)
257  break;
258 
259  if(!visited[neighbors[j]]) //keypoint has not been visited before
260  {
261  visited[neighbors[j]] = true; // mark as visited
262  std::vector<int> further_neighbors;
263  regionQuery(neighbors[j], further_neighbors); //Find more neighbors around the new keypoint
264 // if(further_neighbors.size() < min_pts_)
265 // {
266 // clusters[0].push_back(occupied_cells[neighbors[j]]);
267 // }
268 // else
269  if ((int)further_neighbors.size() >= parameter_.min_pts_)
270  {
271  // neighbors found
272  neighbors.insert(neighbors.end(), further_neighbors.begin(), further_neighbors.end()); //Add these newfound P' neighbour to P neighbour vector "nb_indeces"
273  clusters[cluster_id].push_back(occupied_cells_[neighbors[j]]);
274  }
275  }
276  }
277  }
278  }
279  }
280 }
281 
282 void CostmapToPolygonsDBSMCCH::regionQuery(int curr_index, std::vector<int>& neighbors)
283 {
284  neighbors.clear();
285 
286  double dist_sqr_threshold = parameter_.max_distance_ * parameter_.max_distance_;
287  const KeyPoint& kp = occupied_cells_[curr_index];
288  int cx, cy;
289  pointToNeighborCells(kp, cx,cy);
290 
291  // loop over the neighboring cells for looking up the points
292  const int offsets[9][2] = {{-1, -1}, {0, -1}, {1, -1},
293  {-1, 0}, {0, 0}, {1, 0},
294  {-1, 1}, {0, 1}, {1, 1}};
295  for (int i = 0; i < 9; ++i)
296  {
297  int idx = neighborCellsToIndex(cx + offsets[i][0], cy + offsets[i][1]);
298  if (idx < 0 || idx >= int(neighbor_lookup_.size()))
299  continue;
300  const std::vector<int>& pointIndicesToCheck = neighbor_lookup_[idx];
301  for (int point_idx : pointIndicesToCheck) {
302  if (point_idx == curr_index) // point is not a neighbor to itself
303  continue;
304  const KeyPoint& other = occupied_cells_[point_idx];
305  double dx = other.x - kp.x;
306  double dy = other.y - kp.y;
307  double dist_sqr = dx*dx + dy*dy;
308  if (dist_sqr <= dist_sqr_threshold)
309  neighbors.push_back(point_idx);
310  }
311  }
312 }
313 
315 {
316  return p1.x < p2.x || (p1.x == p2.x && p1.y < p2.y);
317 }
318 
319 void CostmapToPolygonsDBSMCCH::convexHull(std::vector<KeyPoint>& cluster, geometry_msgs::Polygon& polygon)
320 {
321  //Monotone Chain ConvexHull Algorithm source from http://www.algorithmist.com/index.php/Monotone_Chain_Convex_Hull
322 
323  int k = 0;
324  int n = cluster.size();
325 
326  // sort points according to x coordinate (TODO. is it already sorted due to the map representation?)
327  std::sort(cluster.begin(), cluster.end(), isXCoordinateSmaller);
328 
329  polygon.points.resize(2*n);
330 
331  // lower hull
332  for (int i = 0; i < n; ++i)
333  {
334  while (k >= 2 && cross(polygon.points[k-2], polygon.points[k-1], cluster[i]) <= 0)
335  {
336  --k;
337  }
338  cluster[i].toPointMsg(polygon.points[k]);
339  ++k;
340  }
341 
342  // upper hull
343  for (int i = n-2, t = k+1; i >= 0; --i)
344  {
345  while (k >= t && cross(polygon.points[k-2], polygon.points[k-1], cluster[i]) <= 0)
346  {
347  --k;
348  }
349  cluster[i].toPointMsg(polygon.points[k]);
350  ++k;
351  }
352 
353 
354  polygon.points.resize(k); // original
355  // TEST we skip the last point, since in our definition the polygon vertices do not contain the start/end vertex twice.
356 // polygon.points.resize(k-1); // TODO remove last point from the algorithm above to reduce computational cost
357 
358  simplifyPolygon(polygon);
359 }
360 
361 
362 
363 void CostmapToPolygonsDBSMCCH::convexHull2(std::vector<KeyPoint>& cluster, geometry_msgs::Polygon& polygon)
364 {
365  std::vector<KeyPoint>& P = cluster;
366  std::vector<geometry_msgs::Point32>& points = polygon.points;
367 
368  // Sort P by x and y
369  std::sort(P.begin(), P.end(), isXCoordinateSmaller);
370 
371  // the output array H[] will be used as the stack
372  int i; // array scan index
373 
374  // Get the indices of points with min x-coord and min|max y-coord
375  int minmin = 0, minmax;
376  double xmin = P[0].x;
377  for (i = 1; i < (int)P.size(); i++)
378  if (P[i].x != xmin) break;
379  minmax = i - 1;
380  if (minmax == (int)P.size() - 1)
381  { // degenerate case: all x-coords == xmin
382  points.push_back(geometry_msgs::Point32());
383  P[minmin].toPointMsg(points.back());
384  if (P[minmax].y != P[minmin].y) // a nontrivial segment
385  {
386  points.push_back(geometry_msgs::Point32());
387  P[minmax].toPointMsg(points.back());
388  }
389  // add polygon endpoint
390  points.push_back(geometry_msgs::Point32());
391  P[minmin].toPointMsg(points.back());
392  return;
393  }
394 
395  // Get the indices of points with max x-coord and min|max y-coord
396  int maxmin, maxmax = (int)P.size() - 1;
397  double xmax = P.back().x;
398  for (i = P.size() - 2; i >= 0; i--)
399  if (P[i].x != xmax) break;
400  maxmin = i+1;
401 
402  // Compute the lower hull on the stack H
403  // push minmin point onto stack
404  points.push_back(geometry_msgs::Point32());
405  P[minmin].toPointMsg(points.back());
406  i = minmax;
407  while (++i <= maxmin)
408  {
409  // the lower line joins P[minmin] with P[maxmin]
410  if (cross(P[minmin], P[maxmin], P[i]) >= 0 && i < maxmin)
411  continue; // ignore P[i] above or on the lower line
412 
413  while (points.size() > 1) // there are at least 2 points on the stack
414  {
415  // test if P[i] is left of the line at the stack top
416  if (cross(points[points.size() - 2], points.back(), P[i]) > 0)
417  break; // P[i] is a new hull vertex
418  points.pop_back(); // pop top point off stack
419  }
420  // push P[i] onto stack
421  points.push_back(geometry_msgs::Point32());
422  P[i].toPointMsg(points.back());
423  }
424 
425  // Next, compute the upper hull on the stack H above the bottom hull
426  if (maxmax != maxmin) // if distinct xmax points
427  {
428  // push maxmax point onto stack
429  points.push_back(geometry_msgs::Point32());
430  P[maxmax].toPointMsg(points.back());
431  }
432  int bot = (int)points.size(); // the bottom point of the upper hull stack
433  i = maxmin;
434  while (--i >= minmax)
435  {
436  // the upper line joins P[maxmax] with P[minmax]
437  if (cross( P[maxmax], P[minmax], P[i]) >= 0 && i > minmax)
438  continue; // ignore P[i] below or on the upper line
439 
440  while ((int)points.size() > bot) // at least 2 points on the upper stack
441  {
442  // test if P[i] is left of the line at the stack top
443  if (cross(points[points.size() - 2], points.back(), P[i]) > 0)
444  break; // P[i] is a new hull vertex
445  points.pop_back(); // pop top point off stack
446  }
447  // push P[i] onto stack
448  points.push_back(geometry_msgs::Point32());
449  P[i].toPointMsg(points.back());
450  }
451  if (minmax != minmin)
452  {
453  // push joining endpoint onto stack
454  points.push_back(geometry_msgs::Point32());
455  P[minmin].toPointMsg(points.back());
456  }
457 
458  simplifyPolygon(polygon);
459 }
460 
461 void CostmapToPolygonsDBSMCCH::simplifyPolygon(geometry_msgs::Polygon& polygon)
462 {
463  size_t triangleThreshold = 3;
464  // check if first and last point are the same. If yes, a triangle has 4 points
465  if (polygon.points.size() > 1
466  && std::abs(polygon.points.front().x - polygon.points.back().x) < 1e-5
467  && std::abs(polygon.points.front().y - polygon.points.back().y) < 1e-5)
468  {
469  triangleThreshold = 4;
470  }
471  if (polygon.points.size() <= triangleThreshold) // nothing to do for triangles or lines
472  return;
473  // TODO Reason about better start conditions for splitting lines, e.g., by
474  // https://en.wikipedia.org/wiki/Rotating_calipers
475  polygon.points = douglasPeucker(polygon.points.begin(), polygon.points.end(), parameter_.min_keypoint_separation_);;
476 }
477 
479 {
480  boost::mutex::scoped_lock lock(mutex_);
481  polygons_ = polygons;
482 }
483 
484 
486 {
487  boost::mutex::scoped_lock lock(mutex_);
489  return polygons;
490 }
491 
492 void CostmapToPolygonsDBSMCCH::reconfigureCB(CostmapToPolygonsDBSMCCHConfig& config, uint32_t level)
493 {
494  boost::mutex::scoped_lock lock(parameter_mutex_);
495  parameter_buffered_.max_distance_ = config.cluster_max_distance;
496  parameter_buffered_.min_pts_ = config.cluster_min_pts;
497  parameter_buffered_.max_pts_ = config.cluster_max_pts;
498  parameter_buffered_.min_keypoint_separation_ = config.convex_hull_min_pt_separation;
499 }
500 
501 }//end namespace costmap_converter
502 
503 
virtual void updateCostmap2D()
Get updated data from the previously set Costmap2D.
d
void reconfigureCB(CostmapToPolygonsDBSMCCHConfig &config, uint32_t level)
Callback for the dynamic_reconfigure node.
std::vector< KeyPoint > occupied_cells_
List of occupied cells in the current map (updated by updateCostmap2D())
double min_keypoint_separation_
Clear keypoints of the convex polygon that are close to each other [distance in meters] (0: keep all)...
void pointToNeighborCells(const KeyPoint &kp, int &cx, int &cy)
compute the cell indices of a keypoint
static void convertPointToPolygon(const Point &point, geometry_msgs::Polygon &polygon)
Convert a generi point type to a geometry_msgs::Polygon.
void dbScan(std::vector< std::vector< KeyPoint > > &clusters)
DBSCAN algorithm for clustering.
double offset_y_
offset [meters] in x for the lookup grid
void mapToWorld(unsigned int mx, unsigned int my, double &wx, double &wy) const
void simplifyPolygon(geometry_msgs::Polygon &polygon)
Simplify a polygon by removing points.
void addPoint(double x, double y)
helper function for adding a point to the lookup data structures
virtual void compute()
This method performs the actual work (conversion of the costmap to polygons)
int max_pts_
Parameter for DB_Scan: maximum number of points that define a cluster (to avoid large L- and U-shapes...
PLUGINLIB_EXPORT_CLASS(BAGReader, nodelet::Nodelet)
double getOriginX() const
double getSizeInMetersX() const
int neighbor_size_y_
size of the neighbour lookup in x (number of cells)
TFSIMD_FORCE_INLINE const tfScalar & y() const
double getSizeInMetersY() const
virtual void setCostmap2D(costmap_2d::Costmap2D *costmap)
Pass a pointer to the costap to the plugin.
unsigned char getCost(unsigned int mx, unsigned int my) const
costmap_2d::Costmap2D * costmap_
Pointer to the costmap2d.
int neighbor_size_x_
array of cells for neighbor lookup
int min_pts_
Parameter for DB_Scan: minimum number of points that define a cluster.
boost::mutex parameter_mutex_
Mutex that keeps track about the ownership of the shared polygon instance.
double offset_x_
size of the neighbour lookup in y (number of cells)
double max_distance_
Parameter for DB_Scan, maximum distance to neighbors [m].
bool param(const std::string &param_name, T &param_val, const T &default_val) const
double computeSquaredDistanceToLineSegment(const Point &point, const LinePoint &line_start, const LinePoint &line_end, bool *is_inbetween=NULL)
Calculate the squared distance between a point and a straight line segment.
Definition: misc.h:83
This abstract class defines the interface for plugins that convert the costmap into polygon types...
TFSIMD_FORCE_INLINE const tfScalar & x() const
double getOriginY() const
dynamic_reconfigure::Server< CostmapToPolygonsDBSMCCHConfig > * dynamic_recfg_
Dynamic reconfigure server to allow config modifications at runtime.
unsigned int getSizeInCellsY() const
This class converts the costmap_2d into a set of convex polygons (and points)
PolygonContainerPtr polygons_
Current shared container of polygons.
void regionQuery(int curr_index, std::vector< int > &neighbor_indices)
Helper function for dbScan to search for neighboring points.
void convexHull2(std::vector< KeyPoint > &cluster, geometry_msgs::Polygon &polygon)
Compute the convex hull for a single cluster.
unsigned int getSizeInCellsX() const
static const unsigned char LETHAL_OBSTACLE
boost::mutex mutex_
Mutex that keeps track about the ownership of the shared polygon instance.
int neighborCellsToIndex(int cx, int cy)
offset [meters] in y for the lookup grid
bool isXCoordinateSmaller(const CostmapToPolygonsDBSMCCH::KeyPoint &p1, const CostmapToPolygonsDBSMCCH::KeyPoint &p2)
Defines a keypoint in metric coordinates of the map.
void updatePolygonContainer(PolygonContainerPtr polygons)
Thread-safe update of the internal polygon container (that is shared using getPolygons() from outside...
#define ROS_ERROR(...)
void convexHull(std::vector< KeyPoint > &cluster, geometry_msgs::Polygon &polygon)
Compute the convex hull for a single cluster (monotone chain algorithm)
PolygonContainerConstPtr getPolygons()
Get a shared instance of the current polygon container.
std::vector< std::vector< int > > neighbor_lookup_
virtual void initialize(ros::NodeHandle nh)
Initialize the plugin.
long double cross(const P1 &O, const P2 &A, const P3 &B)
2D Cross product of two vectors defined by two points and a common origin


costmap_converter
Author(s): Christoph Rösmann , Franz Albers , Otniel Rinaldo
autogenerated on Sat May 16 2020 03:19:18