Public Member Functions | Static Public Member Functions | Protected Member Functions | Protected Attributes | Private Member Functions | Private Attributes
costmap_converter::CostmapToLinesDBSRANSAC Class Reference

This class converts the costmap_2d into a set of lines (and points) More...

#include <costmap_to_lines_ransac.h>

Inheritance diagram for costmap_converter::CostmapToLinesDBSRANSAC:
Inheritance graph
[legend]

List of all members.

Public Member Functions

virtual void compute ()
 This method performs the actual work (conversion of the costmap to polygons)
 CostmapToLinesDBSRANSAC ()
 Constructor.
virtual void initialize (ros::NodeHandle nh)
 Initialize the plugin.
virtual ~CostmapToLinesDBSRANSAC ()
 Destructor.

Static Public Member Functions

template<typename Point , typename LinePoint >
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.

Protected Member Functions

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'.
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).

Protected Attributes

bool ransac_convert_outlier_pts_
 If true, convert remaining outliers to single points.
bool ransac_filter_remaining_outlier_pts_
 If true, filter the interior of remaining outliers and keep only keypoints of their convex hull.
double ransac_inlier_distance_
 Maximum distance to the line segment for inliers.
int ransac_min_inliers_
 Minimum numer of inliers required to form a line.
int ransac_no_iterations_
 Number of ransac iterations.
int ransac_remainig_outliers_
 Repeat ransac until the number of outliers is as specified here.
boost::random::mt19937 rnd_generator_
 Random number generator for ransac with default seed.

Private Member Functions

void reconfigureCB (CostmapToLinesDBSRANSACConfig &config, uint32_t level)
 Callback for the dynamic_reconfigure node.

Private Attributes

dynamic_reconfigure::Server
< CostmapToLinesDBSRANSACConfig > * 
dynamic_recfg_
 Dynamic reconfigure server to allow config modifications at runtime.

Detailed Description

This class converts the costmap_2d into a set of lines (and points)

The conversion is performed in two stages: 1. Clusters in the costmap are collected using the DBSCAN Algorithm (https://en.wikipedia.org/wiki/DBSCAN) Reference: Ester, Martin; Kriegel, Hans-Peter; Sander, Jörg; Xu, Xiaowei, A density-based algorithm for discovering clusters in large spatial databases with noise. Proceedings of the Second International Conference on Knowledge Discovery and Data Mining. AAAI Press. 1996. pp. 226–231. ISBN 1-57735-004-9.

2. The RANSAC algorithm is used to find straight line segment models (https://en.wikipedia.org/wiki/RANSAC) RANSAC is called repeatedly to find multiple lines per cluster until the number of inliners is below a specific threshold. In that case the remaining outliers are used as points or keypoints of their convex hull are used as points (depending on a paramter). The latter one applies as a filter. The convex assumption is not strict in practice, since the remaining regions/cluster (line inliers are removed) should be dense and small. For details about the convex hull algorithm, refer to costmap_converter::CostmapToPolygonsDBSMCCH. Resulting lines of RANSAC are currently not refined by linear regression.

The output is a container of polygons (but each polygon does only contain a single vertex (point) or two vertices (line)

Definition at line 71 of file costmap_to_lines_ransac.h.


Constructor & Destructor Documentation

Constructor.

Definition at line 49 of file costmap_to_lines_ransac.cpp.

Destructor.

Definition at line 54 of file costmap_to_lines_ransac.cpp.


Member Function Documentation

This method performs the actual work (conversion of the costmap to polygons)

Reimplemented from costmap_converter::CostmapToPolygonsDBSMCCH.

Definition at line 101 of file costmap_to_lines_ransac.cpp.

void costmap_converter::CostmapToLinesDBSRANSAC::initialize ( ros::NodeHandle  nh) [virtual]

Initialize the plugin.

Parameters:
nhNodehandle that defines the namespace for parameters

Reimplemented from costmap_converter::CostmapToPolygonsDBSMCCH.

Definition at line 60 of file costmap_to_lines_ransac.cpp.

template<typename Point , typename LinePoint >
bool costmap_converter::CostmapToLinesDBSRANSAC::isInlier ( const Point &  point,
const LinePoint &  line_start,
const LinePoint &  line_end,
double  min_distance 
) [static]

Check if the candidate point is an inlier.

Parameters:
pointgeneric 2D point type defining the reference point
line_startgeneric 2D point type defining the start of the line
line_endgeneric 2D point type defining the end of the line
min_distanceminimum distance allowed
Template Parameters:
Pointgeneric point type that should provide (writable) x and y member fiels.
LinePointgeneric point type that should provide (writable) x and y member fiels.
Returns:
true if inlier, false otherwise

Definition at line 173 of file costmap_to_lines_ransac.h.

bool costmap_converter::CostmapToLinesDBSRANSAC::linearRegression ( const std::vector< KeyPoint > &  data,
double &  slope,
double &  intercept,
double *  mean_x_out = NULL,
double *  mean_y_out = NULL 
) [protected]

Perform a simple linear regression in order to fit a straight line 'y = slope*x + intercept'.

Parameters:
dataset of 2D data points
[out]slopeThe slope of the fitted line
[out]interceptThe intercept / offset of the line
[out]mean_x_outmean of the x-values of the data [optional]
[out]mean_y_outmean of the y-values of the data [optional]
Returns:
true, if a valid line has been fitted, false otherwise.

Definition at line 250 of file costmap_to_lines_ransac.cpp.

bool costmap_converter::CostmapToLinesDBSRANSAC::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 
) [protected]

Find a straight line segment in a point cloud with RANSAC (without linear regression).

Parameters:
dataset of 2D data points
inlier_distancemaximum distance that inliers must satisfy
no_iterationsnumber of RANSAC iterations
min_inliersminimum number of inliers to return true
[out]best_modelstart and end of the best straight line segment
[out]inliersinlier keypoints are written to this container [optional]
[out]outliersoutlier keypoints are written to this container [optional]
Returns:
false, if min_inliers is not satisfied, true otherwise

Definition at line 176 of file costmap_to_lines_ransac.cpp.

void costmap_converter::CostmapToLinesDBSRANSAC::reconfigureCB ( CostmapToLinesDBSRANSACConfig &  config,
uint32_t  level 
) [private]

Callback for the dynamic_reconfigure node.

This callback allows to modify parameters dynamically at runtime without restarting the node

Parameters:
configReference to the dynamic reconfigure config
levelDynamic reconfigure level

Definition at line 298 of file costmap_to_lines_ransac.cpp.


Member Data Documentation

dynamic_reconfigure::Server<CostmapToLinesDBSRANSACConfig>* costmap_converter::CostmapToLinesDBSRANSAC::dynamic_recfg_ [private]

Dynamic reconfigure server to allow config modifications at runtime.

Reimplemented from costmap_converter::CostmapToPolygonsDBSMCCH.

Definition at line 166 of file costmap_to_lines_ransac.h.

If true, convert remaining outliers to single points.

Definition at line 116 of file costmap_to_lines_ransac.h.

If true, filter the interior of remaining outliers and keep only keypoints of their convex hull.

Definition at line 117 of file costmap_to_lines_ransac.h.

Maximum distance to the line segment for inliers.

Definition at line 112 of file costmap_to_lines_ransac.h.

Minimum numer of inliers required to form a line.

Definition at line 113 of file costmap_to_lines_ransac.h.

Number of ransac iterations.

Definition at line 114 of file costmap_to_lines_ransac.h.

Repeat ransac until the number of outliers is as specified here.

Definition at line 115 of file costmap_to_lines_ransac.h.

Random number generator for ransac with default seed.

Definition at line 120 of file costmap_to_lines_ransac.h.


The documentation for this class was generated from the following files:


costmap_converter
Author(s): Christoph Rösmann , Franz Albers , Otniel Rinaldo
autogenerated on Wed Sep 20 2017 03:00:37