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  nh.param("cluster_max_distance", parameter_.max_distance_, 0.4);
64  nh.param("cluster_min_pts", parameter_.min_pts_, 2);
65  nh.param("cluster_max_pts", parameter_.max_pts_, 30);
66  // convex hull (only necessary if outlier filtering is enabled)
67  nh.param("convex_hull_min_pt_separation", parameter_.min_keypoint_separation_, 0.1);
69 
70  // ransac
71  nh.param("ransac_inlier_distance", ransac_inlier_distance_, 0.2);
72  nh.param("ransac_min_inliers", ransac_min_inliers_, 10);
73  nh.param("ransac_no_iterations", ransac_no_iterations_, 2000);
74  nh.param("ransac_remainig_outliers", ransac_remainig_outliers_, 3);
75  nh.param("ransac_convert_outlier_pts", ransac_convert_outlier_pts_, true);
76  nh.param("ransac_filter_remaining_outlier_pts", ransac_filter_remaining_outlier_pts_, false);
77 
78  // setup dynamic reconfigure
79  dynamic_recfg_ = new dynamic_reconfigure::Server<CostmapToLinesDBSRANSACConfig>(nh);
80  dynamic_reconfigure::Server<CostmapToLinesDBSRANSACConfig>::CallbackType cb = boost::bind(&CostmapToLinesDBSRANSAC::reconfigureCB, this, _1, _2);
81  dynamic_recfg_->setCallback(cb);
82 }
83 
85 {
86  std::vector< std::vector<KeyPoint> > clusters;
87  dbScan(clusters);
88 
89  // Create new polygon container
90  PolygonContainerPtr polygons(new std::vector<geometry_msgs::Polygon>());
91 
92 
93  // fit lines using ransac for each cluster
94  for (int i = 1; i <clusters.size(); ++i) // skip first cluster, since it is just noise
95  {
96 
97  while (clusters[i].size() > ransac_remainig_outliers_)
98  {
99 // std::vector<KeyPoint> inliers;
100  std::vector<KeyPoint> outliers;
101  std::pair<KeyPoint,KeyPoint> model;
102  if (!lineRansac(clusters[i], ransac_inlier_distance_, ransac_no_iterations_, ransac_min_inliers_, model, NULL, &outliers ) )
103  break;
104 
105  // add to polygon container
106  geometry_msgs::Polygon line;
107  line.points.resize(2);
108  model.first.toPointMsg(line.points.front());
109  model.second.toPointMsg(line.points.back());
110  polygons->push_back(line);
111 
112  clusters[i] = outliers;
113  }
114  // create point polygons for remaining outliers
116  {
118  {
119  // take edge points of a convex polygon
120  // these points define a cluster and since all lines are extracted,
121  // we remove points from the interior...
122  geometry_msgs::Polygon polygon;
123  convexHull2(clusters[i], polygon);
124  for (int j=0; j < (int)polygon.points.size(); ++j)
125  {
126  polygons->push_back(geometry_msgs::Polygon());
127  convertPointToPolygon(polygon.points[j], polygons->back());
128  }
129  }
130  else
131  {
132  for (int j = 0; j < (int)clusters[i].size(); ++j)
133  {
134  polygons->push_back(geometry_msgs::Polygon());
135  convertPointToPolygon(clusters[i][j], polygons->back());
136  }
137  }
138 
139  }
140 
141 
142  }
143 
144  // add our non-cluster points to the polygon container (as single points)
145  if (!clusters.empty())
146  {
147  for (int i=0; i < clusters.front().size(); ++i)
148  {
149  polygons->push_back( geometry_msgs::Polygon() );
150  convertPointToPolygon(clusters.front()[i], polygons->back());
151  }
152  }
153 
154  // replace shared polygon container
155  updatePolygonContainer(polygons);
156 }
157 
158 
159 bool CostmapToLinesDBSRANSAC::lineRansac(const std::vector<KeyPoint>& data, double inlier_distance, int no_iterations,
160  int min_inliers, std::pair<KeyPoint, KeyPoint>& best_model,
161  std::vector<KeyPoint>* inliers, std::vector<KeyPoint>* outliers)
162 {
163  if (data.size() < 2 || data.size() < min_inliers)
164  {
165  return false;
166  }
167 
168  boost::random::uniform_int_distribution<> distribution(0, data.size()-1);
169 
170  std::pair<int, int> best_model_idx;
171  int best_no_inliers = -1;
172 
173 
174  for (int i=0; i < no_iterations; ++i)
175  {
176  // choose random points to define a line candidate
177  int start_idx = distribution(rnd_generator_);
178  int end_idx = start_idx;
179  while (end_idx == start_idx)
180  end_idx = distribution(rnd_generator_);
181 
182 
183  // compute inliers
184  int no_inliers = 0;
185  for (int j=0; j<(int)data.size(); ++j)
186  {
187  if ( isInlier(data[j], data[start_idx], data[end_idx], inlier_distance) )
188  ++no_inliers;
189  }
190 
191  if (no_inliers > best_no_inliers)
192  {
193  best_no_inliers = no_inliers;
194  best_model_idx.first = start_idx;
195  best_model_idx.second = end_idx;
196  }
197  }
198 
199  best_model.first = data[best_model_idx.first];
200  best_model.second = data[best_model_idx.second];
201 
202  if (best_no_inliers < min_inliers)
203  return false;
204 
205  // Now repeat the calculation for the best model in order to obtain the inliers and outliers set
206  // This might be faster if no_iterations is large, but TEST
207  if (inliers || outliers)
208  {
209  if (inliers)
210  inliers->clear();
211  if (outliers)
212  outliers->clear();
213 
214  int no_inliers = 0;
215  for (int i=0; i<(int)data.size(); ++i)
216  {
217  if ( isInlier( data[i], best_model.first, best_model.second, inlier_distance ) )
218  {
219  if (inliers)
220  inliers->push_back( data[i] );
221  }
222  else
223  {
224  if (outliers)
225  outliers->push_back( data[i] );
226  }
227  }
228  }
229 
230  return true;
231 }
232 
233 bool CostmapToLinesDBSRANSAC::linearRegression(const std::vector<KeyPoint>& data, double& slope, double& intercept,
234  double* mean_x_out, double* mean_y_out)
235 {
236  if (data.size() < 2)
237  {
238  ROS_ERROR("CostmapToLinesDBSRANSAC: at least 2 data points required for linear regression");
239  return false;
240  }
241 
242  double mean_x = 0;
243  double mean_y = 0;
244  for (int i=0; i<(int)data.size(); ++i)
245  {
246  mean_x += data[i].x;
247  mean_y += data[i].y;
248  }
249  mean_x /= double(data.size());
250  mean_y /= double(data.size());
251 
252  if (mean_x_out)
253  *mean_x_out = mean_x;
254 
255  if (mean_y_out)
256  *mean_y_out = mean_y;
257 
258  double numerator = 0.0;
259  double denominator = 0.0;
260 
261  for(int i=0; i<(int)data.size(); ++i)
262  {
263  double dx = data[i].x - mean_x;
264  numerator += dx * (data[i].y - mean_y);
265  denominator += dx*dx;
266  }
267 
268  if (denominator == 0)
269  {
270  ROS_ERROR("CostmapToLinesDBSRANSAC: linear regression failed, denominator 0");
271  return false;
272  }
273  else
274  slope = numerator / denominator;
275 
276  intercept = mean_y - slope * mean_x;
277  return true;
278 }
279 
280 
281 void CostmapToLinesDBSRANSAC::reconfigureCB(CostmapToLinesDBSRANSACConfig& config, uint32_t level)
282 {
283  boost::mutex::scoped_lock lock(parameter_mutex_);
284  parameter_buffered_.max_distance_ = config.cluster_max_distance;
285  parameter_buffered_.min_pts_ = config.cluster_min_pts;
286  parameter_buffered_.max_pts_ = config.cluster_max_pts;
287  parameter_buffered_.min_keypoint_separation_ = config.cluster_min_pts;
288  ransac_inlier_distance_ = config.ransac_inlier_distance;
289  ransac_min_inliers_ = config.ransac_min_inliers;
290  ransac_no_iterations_ = config.ransac_no_iterations;
291  ransac_remainig_outliers_ = config.ransac_remainig_outliers;
292  ransac_convert_outlier_pts_ = config.ransac_convert_outlier_pts;
293  ransac_filter_remaining_outlier_pts_ = config.ransac_filter_remaining_outlier_pts;
294 }
295 
296 
297 /*
298 void CostmapToLinesDBSRANSAC::adjustLineLength(const std::vector<KeyPoint>& data, const KeyPoint& linept1, const KeyPoint& linept2,
299  KeyPoint& line_start, KeyPoint& line_end)
300 {
301  line_start = linept1;
302  line_end = linept2;
303 
304  // infinite line is defined by linept1 and linept2
305  double dir_x = line_end.x - line_start.x;
306  double dir_y = line_end.y - line_start.y;
307  double norm = std::sqrt(dir_x*dir_x + dir_y*dir_y);
308  dir_x /= norm;
309  dir_y /= norm;
310 
311  // project data onto the line and check if the distance is increased in both directions
312  for (int i=0; i < (int) data.size(); ++i)
313  {
314  double dx = data[i].x - line_start.x;
315  double dy = data[i].y - line_start.y;
316  // check scalar product at start
317  double extension = dx*dir_x + dy*dir_y;
318  if (extension<0)
319  {
320  line_start.x -= dir_x*extension;
321  line_start.y -= dir_y*extension;
322  }
323  else
324  {
325  dx = data[i].x - line_end.x;
326  dy = data[i].y - line_end.y;
327  // check scalar product at end
328  double extension = dx*dir_x + dy*dir_y;
329  if (extension>0)
330  {
331  line_end.x += dir_x*extension;
332  line_end.y += dir_y*extension;
333  }
334  }
335  }
336 
337 }*/
338 
339 
340 }//end namespace costmap_converter
341 
342 
double min_keypoint_separation_
Clear keypoints of the convex polygon that are close to each other [distance in meters] (0: keep all)...
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 ransac_inlier_distance_
Maximum distance to the line segment for inliers.
int max_pts_
Parameter for DB_Scan: maximum number of points that define a cluster (to avoid large L- and U-shapes...
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)
int min_pts_
Parameter for DB_Scan: minimum number of points that define a cluster.
dynamic_reconfigure::Server< CostmapToLinesDBSRANSACConfig > * dynamic_recfg_
Dynamic reconfigure server to allow config modifications at runtime.
boost::mutex parameter_mutex_
Mutex that keeps track about the ownership of the shared polygon instance.
virtual void compute()
This method performs the actual work (conversion of the costmap to polygons)
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
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).
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 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 Sat May 16 2020 03:19:18