Public Member Functions | Public Attributes
sample_consensus::SACModelParallelLines Class Reference

A Sample Consensus Model class for 3D line segmentation. More...

#include <sac_model_parallel_lines.h>

Inheritance diagram for sample_consensus::SACModelParallelLines:
Inheritance graph
[legend]

List of all members.

Public Member Functions

void closestLine (const std::vector< int > &indices, const std::vector< double > &model_coefficients, std::vector< int > *closest_line, std::vector< double > *closest_dist)
 Compute the closest distance between each of a set of points and a pair of parallel lines. Also returns the closest line for each point.
void closestLine (const std::set< int > &indices, const std::vector< double > &model_coefficients, std::vector< int > *closest_line, std::vector< double > *closest_dist)
virtual bool computeModelCoefficients (const std::vector< int > &samples)
 Compute the model coefficients from the samples and store them internally in model_coefficients_. The line coefficients are represented by the points themselves.
virtual bool doSamplesVerifyModel (const std::set< int > &indices, double threshold)
 Verify whether a subset of indices verifies the internal line model coefficients.
virtual void getDistancesToModel (const std::vector< double > &model_coefficients, std::vector< double > &distances)
 Compute all distances from the cloud data to a given parallel lines model.
virtual int getModelType ()
 Return an unique id for this model (SACMODEL_PARALLEL_LINES).
virtual void getSamples (int &iterations, std::vector< int > &samples)
 Get 3 random points as data samples and return them as point indices.
double pointToLineSquareDistance (const geometry_msgs::Point32 &line_point1, const geometry_msgs::Point32 &line_point2, const geometry_msgs::Point32 &point)
 Compute the square distance from a point to a line (as defined by two points).
virtual void projectPoints (const std::vector< int > &inliers, const std::vector< double > &model_coefficients, sensor_msgs::PointCloud &projected_points)
 Create a new point cloud with inliers projected onto the line model.
virtual void projectPointsInPlace (const std::vector< int > &inliers, const std::vector< double > &model_coefficients)
 Project the inliers onto their closest lines in place.
virtual void refitModel (const std::vector< int > &inliers, std::vector< double > &refit_coefficients)
 Recompute the parallel lines coefficients using the given inlier set and return them to the user.
 SACModelParallelLines (double min_line_sep_m, double max_line_sep_m)
 Constructor for base SACModelLine.
virtual void selectWithinDistance (const std::vector< double > &model_coefficients, double threshold, std::vector< int > &inliers)
 Select all the points which respect the given model coefficients as inliers.
bool testModelCoefficients (const std::vector< double > &model_coefficients)
 Test whether the given model coefficients are valid given the input point cloud data.
virtual ~SACModelParallelLines ()
 Destructor for base SACModelLine.

Public Attributes

double max_line_sep_m_
double min_line_sep_m_

Detailed Description

A Sample Consensus Model class for 3D line segmentation.

Definition at line 48 of file sac_model_parallel_lines.h.


Constructor & Destructor Documentation

sample_consensus::SACModelParallelLines::SACModelParallelLines ( double  min_line_sep_m,
double  max_line_sep_m 
) [inline]

Constructor for base SACModelLine.

Definition at line 53 of file sac_model_parallel_lines.h.

Destructor for base SACModelLine.

Definition at line 61 of file sac_model_parallel_lines.h.


Member Function Documentation

void sample_consensus::SACModelParallelLines::closestLine ( const std::vector< int > &  indices,
const std::vector< double > &  model_coefficients,
std::vector< int > *  closest_line,
std::vector< double > *  closest_dist 
)

Compute the closest distance between each of a set of points and a pair of parallel lines. Also returns the closest line for each point.

Parameters:
indicesThe indices of the points in the point cloud.
model_coefficientsThe 3d parallel lines model (length 9). The model is (point on line 1, another point on line 1, point on line 2).
closest_lineThe closest line for each point. 0 means the first line (the one with 2 points listed), 1 means the second line.
closest_distThe distance from each point to its closest line.

Definition at line 76 of file sac_model_parallel_lines.cpp.

void sample_consensus::SACModelParallelLines::closestLine ( const std::set< int > &  indices,
const std::vector< double > &  model_coefficients,
std::vector< int > *  closest_line,
std::vector< double > *  closest_dist 
)

Definition at line 115 of file sac_model_parallel_lines.cpp.

Compute the model coefficients from the samples and store them internally in model_coefficients_. The line coefficients are represented by the points themselves.

Parameters:
samplesThe point indices found as possible good candidates for creating a valid model.

Implements sample_consensus::SACModel.

Definition at line 397 of file sac_model_parallel_lines.cpp.

bool sample_consensus::SACModelParallelLines::doSamplesVerifyModel ( const std::set< int > &  indices,
double  threshold 
) [virtual]

Verify whether a subset of indices verifies the internal line model coefficients.

Parameters:
indicesThe data indices that need to be tested against the line model.
thresholdA maximum admissible distance threshold for determining the inliers from the outliers.

Implements sample_consensus::SACModel.

Definition at line 503 of file sac_model_parallel_lines.cpp.

void sample_consensus::SACModelParallelLines::getDistancesToModel ( const std::vector< double > &  model_coefficients,
std::vector< double > &  distances 
) [virtual]

Compute all distances from the cloud data to a given parallel lines model.

Parameters:
model_coefficientsThe coefficients of a line model that we need to compute distances to. The order is (point on line 1, another point on line 1, point on line 2).
distancesthe resultant estimated distances

Implements sample_consensus::SACModel.

Definition at line 270 of file sac_model_parallel_lines.cpp.

virtual int sample_consensus::SACModelParallelLines::getModelType ( ) [inline, virtual]

Return an unique id for this model (SACMODEL_PARALLEL_LINES).

Implements sample_consensus::SACModel.

Definition at line 85 of file sac_model_parallel_lines.h.

void sample_consensus::SACModelParallelLines::getSamples ( int &  iterations,
std::vector< int > &  samples 
) [virtual]

Get 3 random points as data samples and return them as point indices.

Parameters:
iterationsThe internal number of iterations used by the SAC methods
samplesthe resultant model samples
Note:
Ensures that the 3 points are unique and not co-linear.

Implements sample_consensus::SACModel.

Definition at line 162 of file sac_model_parallel_lines.cpp.

double sample_consensus::SACModelParallelLines::pointToLineSquareDistance ( const geometry_msgs::Point32 &  line_point1,
const geometry_msgs::Point32 &  line_point2,
const geometry_msgs::Point32 &  point 
)

Compute the square distance from a point to a line (as defined by two points).

Parameters:
line_point1One point on the line.
line_point2Another point on the line.
pointThe point

Definition at line 52 of file sac_model_parallel_lines.cpp.

void sample_consensus::SACModelParallelLines::projectPoints ( const std::vector< int > &  inliers,
const std::vector< double > &  model_coefficients,
sensor_msgs::PointCloud projected_points 
) [virtual]

Create a new point cloud with inliers projected onto the line model.

Parameters:
inliersThe indices of the inliers into the data cloud.
model_coefficientsThe coefficients of the parallel lines model.
projected_pointsthe resultant projected points

Implements sample_consensus::SACModel.

Definition at line 287 of file sac_model_parallel_lines.cpp.

void sample_consensus::SACModelParallelLines::projectPointsInPlace ( const std::vector< int > &  inliers,
const std::vector< double > &  model_coefficients 
) [virtual]

Project the inliers onto their closest lines in place.

Parameters:
inliersThe indices of the inliers into the data cloud.
model_coefficientsThe coefficients of the parallel lines model.

Implements sample_consensus::SACModel.

Definition at line 349 of file sac_model_parallel_lines.cpp.

void sample_consensus::SACModelParallelLines::refitModel ( const std::vector< int > &  inliers,
std::vector< double > &  refit_coefficients 
) [virtual]

Recompute the parallel lines coefficients using the given inlier set and return them to the user.

Note:
: These are the coefficients of the line model after refinement.
Parameters:
inliersThe data inliers found as supporting the model.
refit_coefficientsthe resultant recomputed coefficients after non-linear optimization

Implements sample_consensus::SACModel.

Definition at line 421 of file sac_model_parallel_lines.cpp.

void sample_consensus::SACModelParallelLines::selectWithinDistance ( const std::vector< double > &  model_coefficients,
double  threshold,
std::vector< int > &  inliers 
) [virtual]

Select all the points which respect the given model coefficients as inliers.

Parameters:
model_coefficientsThe coefficients of the parallel lines model.
thresholdThe maximum distance from an inlier to its closest line.
inliersthe resultant model inliers
Note:
: To get the refined inliers of a model, use: refined_coeff = refitModel (...); selectWithinDistance (refined_coeff, threshold);

Implements sample_consensus::SACModel.

Definition at line 241 of file sac_model_parallel_lines.cpp.

bool sample_consensus::SACModelParallelLines::testModelCoefficients ( const std::vector< double > &  model_coefficients) [inline, virtual]

Test whether the given model coefficients are valid given the input point cloud data.

Parameters:
model_coefficientsthe model coefficients that need to be tested
Todo:
implement this

Implements sample_consensus::SACModel.

Definition at line 70 of file sac_model_parallel_lines.h.


Member Data Documentation

Definition at line 94 of file sac_model_parallel_lines.h.

Definition at line 93 of file sac_model_parallel_lines.h.


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


door_handle_detector
Author(s): Radu Bogdan Rusu, Marius
autogenerated on Wed Dec 11 2013 14:17:01