pcl::SampleConsensusModelLine< PointT > Class Template Reference

SampleConsensusModelLine defines a model for 3D line segmentation. More...

#include <sac_model_line.h>

Inheritance diagram for pcl::SampleConsensusModelLine< PointT >:
Inheritance graph
[legend]

List of all members.

Public Types

typedef SampleConsensusModel
< PointT >::PointCloud 
PointCloud
typedef SampleConsensusModel
< PointT >::PointCloudConstPtr 
PointCloudConstPtr
typedef SampleConsensusModel
< PointT >::PointCloudPtr 
PointCloudPtr
typedef boost::shared_ptr
< SampleConsensusModelLine
Ptr

Public Member Functions

bool computeModelCoefficients (const std::vector< int > &samples, Eigen::VectorXf &model_coefficients)
 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 a point and a line direction.
bool doSamplesVerifyModel (const std::set< int > &indices, const Eigen::VectorXf &model_coefficients, double threshold)
 Verify whether a subset of indices verifies the given plane model coefficients.
void getDistancesToModel (const Eigen::VectorXf &model_coefficients, std::vector< double > &distances)
 Compute all squared distances from the cloud data to a given line model.
pcl::SacModel getModelType () const
 Return an unique id for this model (SACMODEL_LINE).
void getSamples (int &iterations, std::vector< int > &samples)
 Get 2 random points as data samples and return them as point indices.
void optimizeModelCoefficients (const std::vector< int > &inliers, const Eigen::VectorXf &model_coefficients, Eigen::VectorXf &optimized_coefficients)
 Recompute the line coefficients using the given inlier set and return them to the user.
void projectPoints (const std::vector< int > &inliers, const Eigen::VectorXf &model_coefficients, PointCloud &projected_points, bool copy_data_fields=true)
 Create a new point cloud with inliers projected onto the line model.
 SampleConsensusModelLine (const PointCloudConstPtr &cloud, const std::vector< int > &indices)
 Constructor for base SampleConsensusModelLine.
 SampleConsensusModelLine (const PointCloudConstPtr &cloud)
 Constructor for base SampleConsensusModelLine.
void selectWithinDistance (const Eigen::VectorXf &model_coefficients, double threshold, std::vector< int > &inliers)
 Select all the points which respect the given model coefficients as inliers.

Protected Member Functions

bool isModelValid (const Eigen::VectorXf &model_coefficients)
 Check whether a model is valid given the user constraints.

Static Private Attributes

static const int MAX_ITERATIONS_UNIQUE = 1000
 Define the maximum number of iterations for unique points search.

Detailed Description

template<typename PointT>
class pcl::SampleConsensusModelLine< PointT >

SampleConsensusModelLine defines a model for 3D line segmentation.

Author:
Radu Bogdan Rusu

Definition at line 53 of file sac_model_line.h.


Member Typedef Documentation

template<typename PointT>
typedef SampleConsensusModel<PointT>::PointCloud pcl::SampleConsensusModelLine< PointT >::PointCloud

Reimplemented from pcl::SampleConsensusModel< PointT >.

Reimplemented in pcl::SampleConsensusModelParallelLine< PointT >.

Definition at line 59 of file sac_model_line.h.

template<typename PointT>
typedef SampleConsensusModel<PointT>::PointCloudConstPtr pcl::SampleConsensusModelLine< PointT >::PointCloudConstPtr

Reimplemented from pcl::SampleConsensusModel< PointT >.

Reimplemented in pcl::SampleConsensusModelParallelLine< PointT >.

Definition at line 61 of file sac_model_line.h.

template<typename PointT>
typedef SampleConsensusModel<PointT>::PointCloudPtr pcl::SampleConsensusModelLine< PointT >::PointCloudPtr

Reimplemented from pcl::SampleConsensusModel< PointT >.

Reimplemented in pcl::SampleConsensusModelParallelLine< PointT >.

Definition at line 60 of file sac_model_line.h.

template<typename PointT>
typedef boost::shared_ptr<SampleConsensusModelLine> pcl::SampleConsensusModelLine< PointT >::Ptr

Reimplemented from pcl::SampleConsensusModel< PointT >.

Reimplemented in pcl::SampleConsensusModelParallelLine< PointT >.

Definition at line 63 of file sac_model_line.h.


Constructor & Destructor Documentation

template<typename PointT>
pcl::SampleConsensusModelLine< PointT >::SampleConsensusModelLine ( const PointCloudConstPtr cloud  )  [inline]

Constructor for base SampleConsensusModelLine.

Parameters:
cloud the input point cloud dataset

Definition at line 68 of file sac_model_line.h.

template<typename PointT>
pcl::SampleConsensusModelLine< PointT >::SampleConsensusModelLine ( const PointCloudConstPtr cloud,
const std::vector< int > &  indices 
) [inline]

Constructor for base SampleConsensusModelLine.

Parameters:
cloud the input point cloud dataset
indices a vector of point indices to be used from cloud

Definition at line 74 of file sac_model_line.h.


Member Function Documentation

template<typename PointT >
bool pcl::SampleConsensusModelLine< PointT >::computeModelCoefficients ( const std::vector< int > &  samples,
Eigen::VectorXf &  model_coefficients 
) [inline, 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 a point and a line direction.

Parameters:
samples the point indices found as possible good candidates for creating a valid model
model_coefficients the resultant model coefficients

Implements pcl::SampleConsensusModel< PointT >.

Definition at line 93 of file sac_model_line.hpp.

template<typename PointT >
bool pcl::SampleConsensusModelLine< PointT >::doSamplesVerifyModel ( const std::set< int > &  indices,
const Eigen::VectorXf &  model_coefficients,
double  threshold 
) [inline, virtual]

Verify whether a subset of indices verifies the given plane model coefficients.

Parameters:
indices the data indices that need to be tested against the plane model
model_coefficients the plane model coefficients
threshold a maximum admissible distance threshold for determining the inliers from the outliers

Implements pcl::SampleConsensusModel< PointT >.

Definition at line 306 of file sac_model_line.hpp.

template<typename PointT >
void pcl::SampleConsensusModelLine< PointT >::getDistancesToModel ( const Eigen::VectorXf &  model_coefficients,
std::vector< double > &  distances 
) [inline, virtual]

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

Parameters:
model_coefficients the coefficients of a line model that we need to compute distances to
distances the resultant estimated squared distances

Implements pcl::SampleConsensusModel< PointT >.

Reimplemented in pcl::SampleConsensusModelParallelLine< PointT >.

Definition at line 118 of file sac_model_line.hpp.

template<typename PointT>
pcl::SacModel pcl::SampleConsensusModelLine< PointT >::getModelType (  )  const [inline, virtual]

Return an unique id for this model (SACMODEL_LINE).

Implements pcl::SampleConsensusModel< PointT >.

Reimplemented in pcl::SampleConsensusModelParallelLine< PointT >.

Definition at line 128 of file sac_model_line.h.

template<typename PointT >
void pcl::SampleConsensusModelLine< PointT >::getSamples ( int &  iterations,
std::vector< int > &  samples 
) [inline, virtual]

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

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

Implements pcl::SampleConsensusModel< PointT >.

Definition at line 45 of file sac_model_line.hpp.

template<typename PointT>
bool pcl::SampleConsensusModelLine< PointT >::isModelValid ( const Eigen::VectorXf &  model_coefficients  )  [inline, protected, virtual]

Check whether a model is valid given the user constraints.

Parameters:
model_coefficients the set of model coefficients

Implements pcl::SampleConsensusModel< PointT >.

Reimplemented in pcl::SampleConsensusModelParallelLine< PointT >.

Definition at line 135 of file sac_model_line.h.

template<typename PointT >
void pcl::SampleConsensusModelLine< PointT >::optimizeModelCoefficients ( const std::vector< int > &  inliers,
const Eigen::VectorXf &  model_coefficients,
Eigen::VectorXf &  optimized_coefficients 
) [inline, 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 (eg. after SVD)
Parameters:
inliers the data inliers found as supporting the model
model_coefficients the initial guess for the model coefficients
optimized_coefficients the resultant recomputed coefficients after optimization

Implements pcl::SampleConsensusModel< PointT >.

Definition at line 193 of file sac_model_line.hpp.

template<typename PointT >
void pcl::SampleConsensusModelLine< PointT >::projectPoints ( const std::vector< int > &  inliers,
const Eigen::VectorXf &  model_coefficients,
PointCloud projected_points,
bool  copy_data_fields = true 
) [inline, virtual]

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

Parameters:
inliers the data inliers that we want to project on the line model
model_coefficients the *normalized* coefficients of a line model
projected_points the resultant projected points
copy_data_fields set to true if we need to copy the other data fields

Implements pcl::SampleConsensusModel< PointT >.

Definition at line 236 of file sac_model_line.hpp.

template<typename PointT >
void pcl::SampleConsensusModelLine< PointT >::selectWithinDistance ( const Eigen::VectorXf &  model_coefficients,
double  threshold,
std::vector< int > &  inliers 
) [inline, virtual]

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

Parameters:
model_coefficients the coefficients of a line model that we need to compute distances to
threshold a maximum admissible distance threshold for determining the inliers from the outliers
inliers the resultant model inliers

Implements pcl::SampleConsensusModel< PointT >.

Reimplemented in pcl::SampleConsensusModelParallelLine< PointT >.

Definition at line 148 of file sac_model_line.hpp.


Member Data Documentation

template<typename PointT>
const int pcl::SampleConsensusModelLine< PointT >::MAX_ITERATIONS_UNIQUE = 1000 [static, private]

Define the maximum number of iterations for unique points search.

Definition at line 142 of file sac_model_line.h.


The documentation for this class was generated from the following files:
 All Classes Namespaces Files Functions Variables Typedefs Enumerations Enumerator Friends Defines


pcl
Author(s): See http://pcl.ros.org/authors for the complete list of authors.
autogenerated on Fri Jan 11 09:57:22 2013