Public Member Functions
sample_consensus::SACModelLine Class Reference

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

#include <sac_model_line.h>

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

List of all members.

Public Member Functions

void computeCentroid (const PointCloud &points, const std::vector< int > &indices, pcl::PointXYZ &centroid)
 Compute the centroid of a set of points using their indices and return it as a Point32 message.
void computeCovarianceMatrix (const PointCloud &points, const std::vector< int > &indices, Eigen::Matrix3d &covariance_matrix, pcl::PointXYZ &centroid)
 Compute the 3x3 covariance matrix of a given set of points using their indices. The result is returned as a Eigen::Matrix3d.
virtual bool computeModelCoefficients (const std::vector< int > &samples)
 Check whether the given index samples can form a valid line model, compute the model coefficients from these samples and store them internally in model_coefficients_. The line coefficients are represented by the points themselves.
pcl::PointXYZ cross (const pcl::PointXYZ &p1, const pcl::PointXYZ &p2)
 Compute the cross product between two points (vectors).
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 line model.
virtual int getModelType ()
 Return an unique id for this model (SACMODEL_LINE).
virtual void getSamples (int &iterations, std::vector< int > &samples)
 Get 2 random points as data samples and return them as point indices.
virtual void projectPoints (const std::vector< int > &inliers, const std::vector< double > &model_coefficients, 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 inliers (in place) onto the given line model.
virtual void refitModel (const std::vector< int > &inliers, std::vector< double > &refit_coefficients)
 Recompute the line coefficients using the given inlier set and return them to the user.
 SACModelLine ()
 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 ~SACModelLine ()
 Destructor for base SACModelLine.

Detailed Description

A Sample Consensus Model class for 3D line segmentation.

Definition at line 46 of file sac_model_line.h.


Constructor & Destructor Documentation

Constructor for base SACModelLine.

Definition at line 51 of file sac_model_line.h.

virtual sample_consensus::SACModelLine::~SACModelLine ( ) [inline, virtual]

Destructor for base SACModelLine.

Definition at line 55 of file sac_model_line.h.


Member Function Documentation

void sample_consensus::SACModelLine::computeCentroid ( const PointCloud points,
const std::vector< int > &  indices,
pcl::PointXYZ &  centroid 
) [inline]

Compute the centroid of a set of points using their indices and return it as a Point32 message.

Parameters:
pointsthe input point cloud
indicesthe point cloud indices that need to be used
centroidthe output centroid

Definition at line 103 of file sac_model_line.h.

void sample_consensus::SACModelLine::computeCovarianceMatrix ( const PointCloud points,
const std::vector< int > &  indices,
Eigen::Matrix3d &  covariance_matrix,
pcl::PointXYZ &  centroid 
) [inline]

Compute the 3x3 covariance matrix of a given set of points using their indices. The result is returned as a Eigen::Matrix3d.

Note:
The (x-y-z) centroid is also returned as a Point32 message.
Parameters:
pointsthe input point cloud
indicesthe point cloud indices that need to be used
covariance_matrixthe 3x3 covariance matrix
centroidthe computed centroid

Definition at line 129 of file sac_model_line.h.

bool sample_consensus::SACModelLine::computeModelCoefficients ( const std::vector< int > &  samples) [virtual]

Check whether the given index samples can form a valid line model, compute the model coefficients from these 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 234 of file sac_model_line.cpp.

pcl::PointXYZ sample_consensus::SACModelLine::cross ( const pcl::PointXYZ &  p1,
const pcl::PointXYZ &  p2 
) [inline]

Compute the cross product between two points (vectors).

Parameters:
p1the first point/vector
p2the second point/vector

Definition at line 87 of file sac_model_line.h.

bool sample_consensus::SACModelLine::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 292 of file sac_model_line.cpp.

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

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

Parameters:
model_coefficientsthe coefficients of a line model that we need to compute distances to
distancesthe resultant estimated distances

Implements sample_consensus::SACModel.

Definition at line 140 of file sac_model_line.cpp.

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

Return an unique id for this model (SACMODEL_LINE).

Implements sample_consensus::SACModel.

Definition at line 79 of file sac_model_line.h.

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

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

Parameters:
iterationsthe internal number of iterations used by SAC methods
samplesthe resultant model samples
Note:
assumes unique points!

Implements sample_consensus::SACModel.

Definition at line 52 of file sac_model_line.cpp.

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

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

Parameters:
inliersthe data inliers that we want to project on the line model
model_coefficientsthe coefficients of a line model
projected_pointsthe resultant projected points

Implements sample_consensus::SACModel.

Definition at line 172 of file sac_model_line.cpp.

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

Project inliers (in place) onto the given line model.

Parameters:
inliersthe data inliers that we want to project on the line model
model_coefficientsthe coefficients of a line model

Implements sample_consensus::SACModel.

Definition at line 205 of file sac_model_line.cpp.

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

Recompute the line 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 254 of file sac_model_line.cpp.

void sample_consensus::SACModelLine::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 a line model that we need to compute distances to
thresholda maximum admissible distance threshold for determining the inliers from the outliers
inliersthe resultant model inliers
Note:
: To get the refined inliers of a model, use: ANNpoint refined_coeff = refitModel (...); selectWithinDistance (refined_coeff, threshold);

Implements sample_consensus::SACModel.

Definition at line 90 of file sac_model_line.cpp.

bool sample_consensus::SACModelLine::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 64 of file sac_model_line.h.


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


semantic_point_annotator
Author(s): Radu Bogdan Rusu
autogenerated on Thu Aug 27 2015 14:29:29