costmap_to_lines_ransac.h
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 
39 #ifndef COSTMAP_TO_LINES_RANSAC_H_
40 #define COSTMAP_TO_LINES_RANSAC_H_
41 
44 #include <costmap_converter/misc.h>
45 #include <boost/random.hpp>
46 
47 #include <costmap_converter/CostmapToLinesDBSRANSACConfig.h>
48 
49 namespace costmap_converter
50 {
51 
72  {
73  public:
74 
79 
83  virtual ~CostmapToLinesDBSRANSAC();
84 
89  virtual void initialize(ros::NodeHandle nh);
90 
94  virtual void compute();
95 
96 
107  template <typename Point, typename LinePoint>
108  static bool isInlier(const Point& point, const LinePoint& line_start, const LinePoint& line_end, double min_distance);
109 
110  protected:
111 
118 
119 
120  boost::random::mt19937 rnd_generator_;
121 
122 
134  bool lineRansac(const std::vector<KeyPoint>& data, double inlier_distance, int no_iterations, int min_inliers,
135  std::pair<KeyPoint, KeyPoint>& best_model, std::vector<KeyPoint>* inliers = NULL,
136  std::vector<KeyPoint>* outliers = NULL);
137 
147  bool linearRegression(const std::vector<KeyPoint>& data, double& slope, double& intercept,
148  double* mean_x_out = NULL, double* mean_y_out = NULL);
149 
150 
151 
152 // void adjustLineLength(const std::vector<KeyPoint>& data, const KeyPoint& linept1, const KeyPoint& linept2,
153 // KeyPoint& line_start, KeyPoint& line_end);
154 
155  private:
156 
164  void reconfigureCB(CostmapToLinesDBSRANSACConfig& config, uint32_t level);
165 
166  dynamic_reconfigure::Server<CostmapToLinesDBSRANSACConfig>* dynamic_recfg_;
167 
168  };
169 
170 
171 
172 template <typename Point, typename LinePoint>
173 bool CostmapToLinesDBSRANSAC::isInlier(const Point& point, const LinePoint& line_start, const LinePoint& line_end, double min_distance)
174 {
175  bool is_inbetween = false;
176  double distance = computeDistanceToLineSegment(point, line_start, line_end, &is_inbetween);
177  if (!is_inbetween)
178  return false;
179  if (distance <= min_distance)
180  return true;
181  return false;
182 }
183 
184 
185 } //end namespace teb_local_planner
186 
187 #endif /* COSTMAP_TO_LINES_RANSAC_H_ */
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:118
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.
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)
double distance(double x0, double y0, double x1, double y1)
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 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;...
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.
bool ransac_filter_remaining_outlier_pts_
If true, filter the interior of remaining outliers and keep only keypoints of their convex hull...


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