costmap_to_lines_convex_hull.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 costmap_converter
48 {
49 
50 CostmapToLinesDBSMCCH::CostmapToLinesDBSMCCH() : CostmapToPolygonsDBSMCCH()
51 {
52  dynamic_recfg_ = NULL;
53 }
54 
56 {
57  if (dynamic_recfg_ != NULL)
58  delete dynamic_recfg_;
59 }
60 
62 {
63  // DB SCAN
64  max_distance_ = 0.4;
65  nh.param("cluster_max_distance", max_distance_, max_distance_);
66 
67  min_pts_ = 2;
68  nh.param("cluster_min_pts", min_pts_, min_pts_);
69 
70  max_pts_ = 30;
71  nh.param("cluster_max_pts", max_pts_, max_pts_);
72 
73  // convex hull
75  nh.param("convex_hull_min_pt_separation", min_keypoint_separation_, min_keypoint_separation_);
76 
77  // Line extraction
79  nh.param("support_pts_max_dist", support_pts_max_dist_, support_pts_max_dist_);
80 
82  nh.param("support_pts_max_dist_inbetween", support_pts_max_dist_inbetween_, support_pts_max_dist_inbetween_);
83 
84  min_support_pts_ = 2;
85  nh.param("min_support_pts", min_support_pts_, min_support_pts_);
86 
87  // setup dynamic reconfigure
88  dynamic_recfg_ = new dynamic_reconfigure::Server<CostmapToLinesDBSMCCHConfig>(nh);
89  dynamic_reconfigure::Server<CostmapToLinesDBSMCCHConfig>::CallbackType cb = boost::bind(&CostmapToLinesDBSMCCH::reconfigureCB, this, _1, _2);
90  dynamic_recfg_->setCallback(cb);
91 
92  // deprecated
93  if (nh.hasParam("support_pts_min_dist_") || nh.hasParam("support_pts_min_dist"))
94  ROS_WARN("CostmapToLinesDBSMCCH: Parameter 'support_pts_min_dist' is deprecated and not included anymore.");
95  if (nh.hasParam("min_support_pts_"))
96  ROS_WARN("CostmapToLinesDBSMCCH: Parameter 'min_support_pts_' is not found. Remove the underscore.");
97 }
98 
100 {
101  std::vector< std::vector<KeyPoint> > clusters;
102  dbScan(occupied_cells_, clusters);
103 
104  // Create new polygon container
105  PolygonContainerPtr polygons(new std::vector<geometry_msgs::Polygon>());
106 
107 
108  // add convex hulls to polygon container
109  for (int i = 1; i <clusters.size(); ++i) // skip first cluster, since it is just noise
110  {
111  geometry_msgs::Polygon polygon;
112  convexHull2(clusters[i], polygon );
113 
114  // now extract lines of the polygon (by searching for support points in the cluster)
115  // and add them to the polygon container
116  extractPointsAndLines(clusters[i], polygon, std::back_inserter(*polygons));
117  }
118 
119  // add our non-cluster points to the polygon container (as single points)
120  if (!clusters.empty())
121  {
122  for (int i=0; i < clusters.front().size(); ++i)
123  {
124  polygons->push_back( geometry_msgs::Polygon() );
125  convertPointToPolygon(clusters.front()[i], polygons->back());
126  }
127  }
128 
129  // replace shared polygon container
130  updatePolygonContainer(polygons);
131 }
132 
134 bool sort_keypoint_x(const std::size_t& i, const std::size_t& j, const std::vector<CL::KeyPoint>& cluster)
135 { return (cluster[i].x<cluster[j].x) || (cluster[i].x == cluster[j].x && cluster[i].y < cluster[j].y); }
136 bool sort_keypoint_y(const std::size_t& i, const std::size_t& j, const std::vector<CL::KeyPoint>& cluster)
137 { return (cluster[i].y<cluster[j].y) || (cluster[i].y == cluster[j].y && cluster[i].x < cluster[j].x); }
138 
139 void CostmapToLinesDBSMCCH::extractPointsAndLines(std::vector<KeyPoint>& cluster, const geometry_msgs::Polygon& polygon,
140  std::back_insert_iterator< std::vector<geometry_msgs::Polygon> > lines)
141 {
142  if (polygon.points.empty())
143  return;
144 
145  if (polygon.points.size() < 2)
146  {
147  lines = polygon; // our polygon is just a point, push back onto the output sequence
148  return;
149  }
150  int n = (int)polygon.points.size();
151 
152  for (int i=1; i<n; ++i) // this implemenation requires an explicitly closed polygon (start vertex = end vertex)
153  {
154  const geometry_msgs::Point32* vertex1 = &polygon.points[i-1];
155  const geometry_msgs::Point32* vertex2 = &polygon.points[i];
156 
157  // check how many vertices belong to the line (sometimes the convex hull algorithm finds multiple vertices on a line,
158  // in case of small coordinate deviations)
159  double dx = vertex2->x - vertex1->x;
160  double dy = vertex2->y - vertex1->y;
161 // double norm = std::sqrt(dx*dx + dy*dy);
162 // dx /= norm;
163 // dy /= norm;
164 // for (int j=i; j<(int)polygon.points.size() - 2; ++j)
165 // {
166 // const geometry_msgs::Point32* vertex_jp2 = &polygon.points[j+2];
167 // double dx2 = vertex_jp2->x - vertex2->x;
168 // double dy2 = vertex_jp2->y - vertex2->y;
169 // double norm2 = std::sqrt(dx2*dx2 + dy2*dy2);
170 // dx2 /= norm2;
171 // dy2 /= norm2;
172 // if (std::abs(dx*dx2 + dy*dy2) < 0.05) //~3 degree
173 // {
174 // vertex2 = &polygon.points[j+2];
175 // i = j; // DO NOT USE "i" afterwards
176 // }
177 // else break;
178 // }
179 
180  //Search support points
181  std::vector<std::size_t> support_points; // store indices of cluster
182 
183  for (std::size_t k = 0; k < cluster.size(); ++k)
184  {
185  bool is_inbetween = false;
186  double dist_line_to_point = computeDistanceToLineSegment( cluster[k], *vertex1, *vertex2, &is_inbetween );
187 
188  if(is_inbetween && dist_line_to_point <= support_pts_max_dist_)
189  {
190  support_points.push_back(k);
191  continue;
192  }
193  }
194 
195  // now check if the inlier models a line by checking the minimum distance between all support points (avoid lines over gaps)
196  // and by checking if the minium number of points is reached // deactivate by setting support_pts_max_dist_inbetween_==0
197  bool is_line=true;
199  {
200  if ((int)support_points.size() >= min_support_pts_ + 2) // +2 since start and goal are included
201  {
202  // sort points
203  if (std::abs(dx) >= std::abs(dy))
204  std::sort(support_points.begin(), support_points.end(), boost::bind(sort_keypoint_x, _1, _2, boost::cref(cluster)));
205  else
206  std::sort(support_points.begin(), support_points.end(), boost::bind(sort_keypoint_y, _1, _2, boost::cref(cluster)));
207 
208  // now calculate distances
209  for (int k = 1; k < int(support_points.size()); ++k)
210  {
211  double dist_x = cluster[support_points[k]].x - cluster[support_points[k-1]].x;
212  double dist_y = cluster[support_points[k]].y - cluster[support_points[k-1]].y;
213  double dist = std::sqrt( dist_x*dist_x + dist_y*dist_y);
215  {
216  is_line = false;
217  break;
218  }
219  }
220 
221  }
222  else
223  is_line = false;
224  }
225 
226  if (is_line)
227  {
228  // line found:
229  geometry_msgs::Polygon line;
230  line.points.push_back(*vertex1);
231  line.points.push_back(*vertex2);
232  lines = line; // back insertion
233 
234  // remove inlier from list
235  // iterate in reverse order, otherwise indices are not valid after erasing elements
236  std::vector<std::size_t>::reverse_iterator support_it = support_points.rbegin();
237  for (; support_it != support_points.rend(); ++support_it)
238  {
239  cluster.erase(cluster.begin() + *support_it);
240  }
241  }
242  else
243  {
244  // remove goal, since it will be added in the subsequent iteration
245  //support_points.pop_back();
246  // old:
247 // // add vertex 1 as single point
248 // geometry_msgs::Polygon point;
249 // point.points.push_back(*vertex1);
250 // lines = point; // back insertion
251 
252  // add complete inlier set as points
253 // for (int k = 0; k < int(support_points.size()); ++k)
254 // {
255 // geometry_msgs::Polygon polygon;
256 // convertPointToPolygon(cluster[support_points[k]], polygon);
257 // lines = polygon; // back insertion
258 // }
259 
260  // remove inlier from list and add them as point obstacles
261  // iterate in reverse order, otherwise indices are not valid after erasing elements
262  std::vector<std::size_t>::reverse_iterator support_it = support_points.rbegin();
263  for (; support_it != support_points.rend(); ++support_it)
264  {
265  geometry_msgs::Polygon polygon;
266  convertPointToPolygon(cluster[*support_it], polygon);
267  lines = polygon; // back insertion
268 
269  cluster.erase(cluster.begin() + *support_it);
270  }
271  }
272  }
273 
274  // add all remaining cluster points, that do not belong to a line
275  for (int i=0; i<(int)cluster.size();++i)
276  {
277  geometry_msgs::Polygon polygon;
278  convertPointToPolygon(cluster[i], polygon);
279  lines = polygon; // back insertion
280  }
281 
282 }
283 
284 void CostmapToLinesDBSMCCH::reconfigureCB(CostmapToLinesDBSMCCHConfig& config, uint32_t level)
285 {
286  max_distance_ = config.cluster_max_distance;
287  min_pts_ = config.cluster_min_pts;
288  max_pts_ = config.cluster_max_pts;
289  min_keypoint_separation_ = config.cluster_min_pts;
290  support_pts_max_dist_ = config.support_pts_max_dist;
291  support_pts_max_dist_inbetween_ = config.support_pts_max_dist_inbetween;
292  min_support_pts_ = config.min_support_pts;
293 }
294 
295 
296 
297 }//end namespace costmap_converter
298 
299 
virtual void compute()
This method performs the actual work (conversion of the costmap to polygons)
std::vector< KeyPoint > occupied_cells_
List of occupied cells in the current map (updated by updateCostmap2D())
virtual void initialize(ros::NodeHandle nh)
Initialize the plugin.
int max_pts_
Parameter for DB_Scan: maximum number of points that define a cluster (to avoid large L- and U-shapes...
static void convertPointToPolygon(const Point &point, geometry_msgs::Polygon &polygon)
Convert a generi point type to a geometry_msgs::Polygon.
This class converts the costmap_2d into a set of lines (and points)
bool sort_keypoint_x(const std::size_t &i, const std::size_t &j, const std::vector< CL::KeyPoint > &cluster)
double max_distance_
Parameter for DB_Scan, maximum distance to neighbors [m].
double computeDistanceToLineSegment(const Point &point, const LinePoint &line_start, const LinePoint &line_end, bool *is_inbetween=NULL)
Calculate the distance between a point and a straight line segment.
Definition: misc.h:83
double min_keypoint_separation_
Clear keypoints of the convex polygon that are close to each other [distance in meters] (0: keep all)...
PLUGINLIB_EXPORT_CLASS(BAGReader, nodelet::Nodelet)
TFSIMD_FORCE_INLINE const tfScalar & y() const
#define ROS_WARN(...)
dynamic_reconfigure::Server< CostmapToLinesDBSMCCHConfig > * dynamic_recfg_
Dynamic reconfigure server to allow config modifications at runtime.
bool param(const std::string &param_name, T &param_val, const T &default_val) const
bool sort_keypoint_y(const std::size_t &i, const std::size_t &j, const std::vector< CL::KeyPoint > &cluster)
This abstract class defines the interface for plugins that convert the costmap into polygon types...
TFSIMD_FORCE_INLINE const tfScalar & x() const
int min_pts_
Parameter for DB_Scan: minimum number of points that define a cluster.
This class converts the costmap_2d into a set of convex polygons (and points)
void dbScan(const std::vector< KeyPoint > &occupied_cells, std::vector< std::vector< KeyPoint > > &clusters)
DBSCAN algorithm for clustering.
void convexHull2(std::vector< KeyPoint > &cluster, geometry_msgs::Polygon &polygon)
Compute the convex hull for a single cluster.
void reconfigureCB(CostmapToLinesDBSMCCHConfig &config, uint32_t level)
Callback for the dynamic_reconfigure node.
void extractPointsAndLines(std::vector< KeyPoint > &cluster, const geometry_msgs::Polygon &polygon, std::back_insert_iterator< std::vector< geometry_msgs::Polygon > > lines)
Extract points and lines from a given cluster by checking all keypoint pairs of the convex hull for a...
bool hasParam(const std::string &key) const
void updatePolygonContainer(PolygonContainerPtr polygons)
Thread-safe update of the internal polygon container (that is shared using getPolygons() from outside...


costmap_converter
Author(s): Christoph Rösmann , Franz Albers , Otniel Rinaldo
autogenerated on Fri Jun 7 2019 21:48:43