costmap_to_lines_ransac.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
37  *********************************************************************/
38 
40 #include <boost/thread.hpp>
41 #include <boost/thread/mutex.hpp>
43 
45 
46 namespace costmap_converter
47 {
48 
49 CostmapToLinesDBSRANSAC::CostmapToLinesDBSRANSAC() : CostmapToPolygonsDBSMCCH()
50 {
51  dynamic_recfg_ = NULL;
52 }
53 
55 {
56  if (dynamic_recfg_ != NULL)
57  delete dynamic_recfg_;
58 }
59 
61 {
62  // DB SCAN
63  max_distance_ = 0.4;
64  nh.param("cluster_max_distance", max_distance_, max_distance_);
65 
66  min_pts_ = 2;
67  nh.param("cluster_min_pts", min_pts_, min_pts_);
68 
69  max_pts_ = 30;
70  nh.param("cluster_max_pts", max_pts_, max_pts_);
71 
72  // ransac
74  nh.param("ransac_inlier_distance", ransac_inlier_distance_, ransac_inlier_distance_);
75 
77  nh.param("ransac_min_inliers", ransac_min_inliers_, ransac_min_inliers_);
78 
79  ransac_no_iterations_ = 2000;
80  nh.param("ransac_no_iterations", ransac_no_iterations_, ransac_no_iterations_);
81 
83  nh.param("ransac_remainig_outliers", ransac_remainig_outliers_, ransac_remainig_outliers_);
84 
86  nh.param("ransac_convert_outlier_pts", ransac_convert_outlier_pts_, ransac_convert_outlier_pts_);
87 
89  nh.param("ransac_filter_remaining_outlier_pts", ransac_filter_remaining_outlier_pts_, ransac_filter_remaining_outlier_pts_);
90 
91  // convex hull (only necessary if outlier filtering is enabled)
93  nh.param("convex_hull_min_pt_separation", min_keypoint_separation_, min_keypoint_separation_);
94 
95  // setup dynamic reconfigure
96  dynamic_recfg_ = new dynamic_reconfigure::Server<CostmapToLinesDBSRANSACConfig>(nh);
97  dynamic_reconfigure::Server<CostmapToLinesDBSRANSACConfig>::CallbackType cb = boost::bind(&CostmapToLinesDBSRANSAC::reconfigureCB, this, _1, _2);
98  dynamic_recfg_->setCallback(cb);
99 }
100 
102 {
103  std::vector< std::vector<KeyPoint> > clusters;
104  dbScan(occupied_cells_, clusters);
105 
106  // Create new polygon container
107  PolygonContainerPtr polygons(new std::vector<geometry_msgs::Polygon>());
108 
109 
110  // fit lines using ransac for each cluster
111  for (int i = 1; i <clusters.size(); ++i) // skip first cluster, since it is just noise
112  {
113 
114  while (clusters[i].size() > ransac_remainig_outliers_)
115  {
116 // std::vector<KeyPoint> inliers;
117  std::vector<KeyPoint> outliers;
118  std::pair<KeyPoint,KeyPoint> model;
119  if (!lineRansac(clusters[i], ransac_inlier_distance_, ransac_no_iterations_, ransac_min_inliers_, model, NULL, &outliers ) )
120  break;
121 
122  // add to polygon container
123  geometry_msgs::Polygon line;
124  line.points.resize(2);
125  model.first.toPointMsg(line.points.front());
126  model.second.toPointMsg(line.points.back());
127  polygons->push_back(line);
128 
129  clusters[i] = outliers;
130  }
131  // create point polygons for remaining outliers
133  {
135  {
136  // take edge points of a convex polygon
137  // these points define a cluster and since all lines are extracted,
138  // we remove points from the interior...
139  geometry_msgs::Polygon polygon;
140  convexHull2(clusters[i], polygon);
141  for (int j=0; j < (int)polygon.points.size(); ++j)
142  {
143  polygons->push_back(geometry_msgs::Polygon());
144  convertPointToPolygon(polygon.points[j], polygons->back());
145  }
146  }
147  else
148  {
149  for (int j = 0; j < (int)clusters[i].size(); ++j)
150  {
151  polygons->push_back(geometry_msgs::Polygon());
152  convertPointToPolygon(clusters[i][j], polygons->back());
153  }
154  }
155 
156  }
157 
158 
159  }
160 
161  // add our non-cluster points to the polygon container (as single points)
162  if (!clusters.empty())
163  {
164  for (int i=0; i < clusters.front().size(); ++i)
165  {
166  polygons->push_back( geometry_msgs::Polygon() );
167  convertPointToPolygon(clusters.front()[i], polygons->back());
168  }
169  }
170 
171  // replace shared polygon container
172  updatePolygonContainer(polygons);
173 }
174 
175 
176 bool CostmapToLinesDBSRANSAC::lineRansac(const std::vector<KeyPoint>& data, double inlier_distance, int no_iterations,
177  int min_inliers, std::pair<KeyPoint, KeyPoint>& best_model,
178  std::vector<KeyPoint>* inliers, std::vector<KeyPoint>* outliers)
179 {
180  if (data.size() < 2 || data.size() < min_inliers)
181  {
182  return false;
183  }
184 
185  boost::random::uniform_int_distribution<> distribution(0, data.size()-1);
186 
187  std::pair<int, int> best_model_idx;
188  int best_no_inliers = -1;
189 
190 
191  for (int i=0; i < no_iterations; ++i)
192  {
193  // choose random points to define a line candidate
194  int start_idx = distribution(rnd_generator_);
195  int end_idx = start_idx;
196  while (end_idx == start_idx)
197  end_idx = distribution(rnd_generator_);
198 
199 
200  // compute inliers
201  int no_inliers = 0;
202  for (int j=0; j<(int)data.size(); ++j)
203  {
204  if ( isInlier(data[j], data[start_idx], data[end_idx], inlier_distance) )
205  ++no_inliers;
206  }
207 
208  if (no_inliers > best_no_inliers)
209  {
210  best_no_inliers = no_inliers;
211  best_model_idx.first = start_idx;
212  best_model_idx.second = end_idx;
213  }
214  }
215 
216  best_model.first = data[best_model_idx.first];
217  best_model.second = data[best_model_idx.second];
218 
219  if (best_no_inliers < min_inliers)
220  return false;
221 
222  // Now repeat the calculation for the best model in order to obtain the inliers and outliers set
223  // This might be faster if no_iterations is large, but TEST
224  if (inliers || outliers)
225  {
226  if (inliers)
227  inliers->clear();
228  if (outliers)
229  outliers->clear();
230 
231  int no_inliers = 0;
232  for (int i=0; i<(int)data.size(); ++i)
233  {
234  if ( isInlier( data[i], best_model.first, best_model.second, inlier_distance ) )
235  {
236  if (inliers)
237  inliers->push_back( data[i] );
238  }
239  else
240  {
241  if (outliers)
242  outliers->push_back( data[i] );
243  }
244  }
245  }
246 
247  return true;
248 }
249 
250 bool CostmapToLinesDBSRANSAC::linearRegression(const std::vector<KeyPoint>& data, double& slope, double& intercept,
251  double* mean_x_out, double* mean_y_out)
252 {
253  if (data.size() < 2)
254  {
255  ROS_ERROR("CostmapToLinesDBSRANSAC: at least 2 data points required for linear regression");
256  return false;
257  }
258 
259  double mean_x = 0;
260  double mean_y = 0;
261  for (int i=0; i<(int)data.size(); ++i)
262  {
263  mean_x += data[i].x;
264  mean_y += data[i].y;
265  }
266  mean_x /= double(data.size());
267  mean_y /= double(data.size());
268 
269  if (mean_x_out)
270  *mean_x_out = mean_x;
271 
272  if (mean_y_out)
273  *mean_y_out = mean_y;
274 
275  double numerator = 0.0;
276  double denominator = 0.0;
277 
278  for(int i=0; i<(int)data.size(); ++i)
279  {
280  double dx = data[i].x - mean_x;
281  numerator += dx * (data[i].y - mean_y);
282  denominator += dx*dx;
283  }
284 
285  if (denominator == 0)
286  {
287  ROS_ERROR("CostmapToLinesDBSRANSAC: linear regression failed, denominator 0");
288  return false;
289  }
290  else
291  slope = numerator / denominator;
292 
293  intercept = mean_y - slope * mean_x;
294  return true;
295 }
296 
297 
298 void CostmapToLinesDBSRANSAC::reconfigureCB(CostmapToLinesDBSRANSACConfig& config, uint32_t level)
299 {
300  max_distance_ = config.cluster_max_distance;
301  min_pts_ = config.cluster_min_pts;
302  max_pts_ = config.cluster_max_pts;
303  ransac_inlier_distance_ = config.ransac_inlier_distance;
304  ransac_min_inliers_ = config.ransac_min_inliers;
305  ransac_no_iterations_ = config.ransac_no_iterations;
306  ransac_remainig_outliers_ = config.ransac_remainig_outliers;
307  ransac_convert_outlier_pts_ = config.ransac_convert_outlier_pts;
308  ransac_filter_remaining_outlier_pts_ = config.ransac_filter_remaining_outlier_pts;
309  min_keypoint_separation_ = config.cluster_min_pts;
310 }
311 
312 
313 /*
314 void CostmapToLinesDBSRANSAC::adjustLineLength(const std::vector<KeyPoint>& data, const KeyPoint& linept1, const KeyPoint& linept2,
315  KeyPoint& line_start, KeyPoint& line_end)
316 {
317  line_start = linept1;
318  line_end = linept2;
319 
320  // infinite line is defined by linept1 and linept2
321  double dir_x = line_end.x - line_start.x;
322  double dir_y = line_end.y - line_start.y;
323  double norm = std::sqrt(dir_x*dir_x + dir_y*dir_y);
324  dir_x /= norm;
325  dir_y /= norm;
326 
327  // project data onto the line and check if the distance is increased in both directions
328  for (int i=0; i < (int) data.size(); ++i)
329  {
330  double dx = data[i].x - line_start.x;
331  double dy = data[i].y - line_start.y;
332  // check scalar product at start
333  double extension = dx*dir_x + dy*dir_y;
334  if (extension<0)
335  {
336  line_start.x -= dir_x*extension;
337  line_start.y -= dir_y*extension;
338  }
339  else
340  {
341  dx = data[i].x - line_end.x;
342  dy = data[i].y - line_end.y;
343  // check scalar product at end
344  double extension = dx*dir_x + dy*dir_y;
345  if (extension>0)
346  {
347  line_end.x += dir_x*extension;
348  line_end.y += dir_y*extension;
349  }
350  }
351  }
352 
353 }*/
354 
355 
356 }//end namespace costmap_converter
357 
358 
std::vector< KeyPoint > occupied_cells_
List of occupied cells in the current map (updated by updateCostmap2D())
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.
double max_distance_
Parameter for DB_Scan, maximum distance to neighbors [m].
double min_keypoint_separation_
Clear keypoints of the convex polygon that are close to each other [distance in meters] (0: keep all)...
double ransac_inlier_distance_
Maximum distance to the line segment for inliers.
virtual void initialize(ros::NodeHandle nh)
Initialize the plugin.
bool ransac_convert_outlier_pts_
If true, convert remaining outliers to single points.
PLUGINLIB_EXPORT_CLASS(BAGReader, nodelet::Nodelet)
int ransac_min_inliers_
Minimum numer of inliers required to form a line.
boost::random::mt19937 rnd_generator_
Random number generator for ransac with default seed.
int ransac_no_iterations_
Number of ransac iterations.
int ransac_remainig_outliers_
Repeat ransac until the number of outliers is as specified here.
This class converts the costmap_2d into a set of lines (and points)
dynamic_reconfigure::Server< CostmapToLinesDBSRANSACConfig > * dynamic_recfg_
Dynamic reconfigure server to allow config modifications at runtime.
virtual void compute()
This method performs the actual work (conversion of the costmap to polygons)
bool param(const std::string &param_name, T &param_val, const T &default_val) const
This abstract class defines the interface for plugins that convert the costmap into polygon types...
bool lineRansac(const std::vector< KeyPoint > &data, double inlier_distance, int no_iterations, int min_inliers, std::pair< KeyPoint, KeyPoint > &best_model, std::vector< KeyPoint > *inliers=NULL, std::vector< KeyPoint > *outliers=NULL)
Find a straight line segment in a point cloud with RANSAC (without linear regression).
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 reconfigureCB(CostmapToLinesDBSRANSACConfig &config, uint32_t level)
Callback for the dynamic_reconfigure node.
bool linearRegression(const std::vector< KeyPoint > &data, double &slope, double &intercept, double *mean_x_out=NULL, double *mean_y_out=NULL)
Perform a simple linear regression in order to fit a straight line &#39;y = slope*x + intercept&#39;...
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.
static bool isInlier(const Point &point, const LinePoint &line_start, const LinePoint &line_end, double min_distance)
Check if the candidate point is an inlier.
void updatePolygonContainer(PolygonContainerPtr polygons)
Thread-safe update of the internal polygon container (that is shared using getPolygons() from outside...
bool ransac_filter_remaining_outlier_pts_
If true, filter the interior of remaining outliers and keep only keypoints of their convex hull...
#define ROS_ERROR(...)


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