40 #include <boost/thread.hpp> 41 #include <boost/thread/mutex.hpp> 79 dynamic_recfg_ =
new dynamic_reconfigure::Server<CostmapToLinesDBSRANSACConfig>(nh);
86 std::vector< std::vector<KeyPoint> > clusters;
94 for (
int i = 1; i <clusters.size(); ++i)
100 std::vector<KeyPoint> outliers;
101 std::pair<KeyPoint,KeyPoint> model;
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);
112 clusters[i] = outliers;
122 geometry_msgs::Polygon polygon;
124 for (
int j=0; j < (int)polygon.points.size(); ++j)
126 polygons->push_back(geometry_msgs::Polygon());
132 for (
int j = 0; j < (int)clusters[i].size(); ++j)
134 polygons->push_back(geometry_msgs::Polygon());
145 if (!clusters.empty())
147 for (
int i=0; i < clusters.front().size(); ++i)
149 polygons->push_back( geometry_msgs::Polygon() );
160 int min_inliers, std::pair<KeyPoint, KeyPoint>& best_model,
161 std::vector<KeyPoint>* inliers, std::vector<KeyPoint>* outliers)
163 if (data.size() < 2 || data.size() < min_inliers)
168 boost::random::uniform_int_distribution<> distribution(0, data.size()-1);
170 std::pair<int, int> best_model_idx;
171 int best_no_inliers = -1;
174 for (
int i=0; i < no_iterations; ++i)
178 int end_idx = start_idx;
179 while (end_idx == start_idx)
185 for (
int j=0; j<(int)data.size(); ++j)
187 if (
isInlier(data[j], data[start_idx], data[end_idx], inlier_distance) )
191 if (no_inliers > best_no_inliers)
193 best_no_inliers = no_inliers;
194 best_model_idx.first = start_idx;
195 best_model_idx.second = end_idx;
199 best_model.first = data[best_model_idx.first];
200 best_model.second = data[best_model_idx.second];
202 if (best_no_inliers < min_inliers)
207 if (inliers || outliers)
215 for (
int i=0; i<(int)data.size(); ++i)
217 if (
isInlier( data[i], best_model.first, best_model.second, inlier_distance ) )
220 inliers->push_back( data[i] );
225 outliers->push_back( data[i] );
234 double* mean_x_out,
double* mean_y_out)
238 ROS_ERROR(
"CostmapToLinesDBSRANSAC: at least 2 data points required for linear regression");
244 for (
int i=0; i<(int)data.size(); ++i)
249 mean_x /= double(data.size());
250 mean_y /= double(data.size());
253 *mean_x_out = mean_x;
256 *mean_y_out = mean_y;
258 double numerator = 0.0;
259 double denominator = 0.0;
261 for(
int i=0; i<(int)data.size(); ++i)
263 double dx = data[i].x - mean_x;
264 numerator += dx * (data[i].y - mean_y);
265 denominator += dx*dx;
268 if (denominator == 0)
270 ROS_ERROR(
"CostmapToLinesDBSRANSAC: linear regression failed, denominator 0");
274 slope = numerator / denominator;
276 intercept = mean_y - slope * mean_x;
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.
virtual ~CostmapToLinesDBSRANSAC()
Destructor.
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 ¶m_name, T ¶m_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 'y = slope*x + intercept'...
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...
Parameters parameter_buffered_
bool ransac_filter_remaining_outlier_pts_
If true, filter the interior of remaining outliers and keep only keypoints of their convex hull...