Public Types | Public Member Functions | Protected Member Functions
pcl::SampleConsensusModelStick< PointT > Class Template Reference

SampleConsensusModelStick defines a model for 3D stick segmentation. A stick is a line with an user given minimum/maximum width. The model coefficients are defined as: More...

#include <sac_model_stick.h>

Inheritance diagram for pcl::SampleConsensusModelStick< 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
< SampleConsensusModelStick
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 stick model, compute the model coefficients from these samples and store them internally in model_coefficients_. The stick coefficients are represented by a point and a line direction.
virtual int countWithinDistance (const Eigen::VectorXf &model_coefficients, const double threshold)
 Count all the points which respect the given model coefficients as inliers.
bool doSamplesVerifyModel (const std::set< int > &indices, const Eigen::VectorXf &model_coefficients, const double threshold)
 Verify whether a subset of indices verifies the given stick model coefficients.
void getDistancesToModel (const Eigen::VectorXf &model_coefficients, std::vector< double > &distances)
 Compute all squared distances from the cloud data to a given stick model.
pcl::SacModel getModelType () const
 Return an unique id for this model (SACMODEL_STACK).
void optimizeModelCoefficients (const std::vector< int > &inliers, const Eigen::VectorXf &model_coefficients, Eigen::VectorXf &optimized_coefficients)
 Recompute the stick 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 stick model.
 SampleConsensusModelStick (const PointCloudConstPtr &cloud)
 Constructor for base SampleConsensusModelStick.
 SampleConsensusModelStick (const PointCloudConstPtr &cloud, const std::vector< int > &indices)
 Constructor for base SampleConsensusModelStick.
void selectWithinDistance (const Eigen::VectorXf &model_coefficients, const 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.
bool isSampleGood (const std::vector< int > &samples) const
 Check if a sample of indices results in a good sample of points indices.

Detailed Description

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

SampleConsensusModelStick defines a model for 3D stick segmentation. A stick is a line with an user given minimum/maximum width. The model coefficients are defined as:

Definition at line 63 of file sac_model_stick.h.


Member Typedef Documentation

Reimplemented from pcl::SampleConsensusModel< PointT >.

Definition at line 71 of file sac_model_stick.h.

Reimplemented from pcl::SampleConsensusModel< PointT >.

Definition at line 73 of file sac_model_stick.h.

Reimplemented from pcl::SampleConsensusModel< PointT >.

Definition at line 72 of file sac_model_stick.h.

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

Reimplemented from pcl::SampleConsensusModel< PointT >.

Definition at line 75 of file sac_model_stick.h.


Constructor & Destructor Documentation

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

Constructor for base SampleConsensusModelStick.

Parameters:
[in]cloudthe input point cloud dataset

Definition at line 80 of file sac_model_stick.h.

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

Constructor for base SampleConsensusModelStick.

Parameters:
[in]cloudthe input point cloud dataset
[in]indicesa vector of point indices to be used from cloud

Definition at line 86 of file sac_model_stick.h.


Member Function Documentation

template<typename PointT >
bool pcl::SampleConsensusModelStick< PointT >::computeModelCoefficients ( const std::vector< int > &  samples,
Eigen::VectorXf &  model_coefficients 
) [virtual]

Check whether the given index samples can form a valid stick model, compute the model coefficients from these samples and store them internally in model_coefficients_. The stick coefficients are represented by a point and a line direction.

Parameters:
[in]samplesthe point indices found as possible good candidates for creating a valid model
[out]model_coefficientsthe resultant model coefficients

Implements pcl::SampleConsensusModel< PointT >.

Definition at line 62 of file sac_model_stick.hpp.

template<typename PointT >
int pcl::SampleConsensusModelStick< PointT >::countWithinDistance ( const Eigen::VectorXf &  model_coefficients,
const double  threshold 
) [virtual]

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

Parameters:
[in]model_coefficientsthe coefficients of a model that we need to compute distances to
[in]thresholdmaximum admissible distance threshold for determining the inliers from the outliers
Returns:
the resultant number of inliers

Implements pcl::SampleConsensusModel< PointT >.

Definition at line 169 of file sac_model_stick.hpp.

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

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

Parameters:
[in]indicesthe data indices that need to be tested against the plane model
[in]model_coefficientsthe plane model coefficients
[in]thresholda maximum admissible distance threshold for determining the inliers from the outliers

Implements pcl::SampleConsensusModel< PointT >.

Definition at line 328 of file sac_model_stick.hpp.

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

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

Parameters:
[in]model_coefficientsthe coefficients of a stick model that we need to compute distances to
[out]distancesthe resultant estimated squared distances

Implements pcl::SampleConsensusModel< PointT >.

Definition at line 93 of file sac_model_stick.hpp.

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

Return an unique id for this model (SACMODEL_STACK).

Implements pcl::SampleConsensusModel< PointT >.

Definition at line 161 of file sac_model_stick.h.

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

Check whether a model is valid given the user constraints.

Parameters:
[in]model_coefficientsthe set of model coefficients

Implements pcl::SampleConsensusModel< PointT >.

Definition at line 168 of file sac_model_stick.h.

template<typename PointT >
bool pcl::SampleConsensusModelStick< PointT >::isSampleGood ( const std::vector< int > &  samples) const [protected, virtual]

Check if a sample of indices results in a good sample of points indices.

Parameters:
[in]samplesthe resultant index samples

Implements pcl::SampleConsensusModel< PointT >.

Definition at line 47 of file sac_model_stick.hpp.

template<typename PointT >
void pcl::SampleConsensusModelStick< PointT >::optimizeModelCoefficients ( const std::vector< int > &  inliers,
const Eigen::VectorXf &  model_coefficients,
Eigen::VectorXf &  optimized_coefficients 
) [virtual]

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

Note:
: these are the coefficients of the stick model after refinement (eg. after SVD)
Parameters:
[in]inliersthe data inliers found as supporting the model
[in]model_coefficientsthe initial guess for the model coefficients
[out]optimized_coefficientsthe resultant recomputed coefficients after optimization

Implements pcl::SampleConsensusModel< PointT >.

Definition at line 214 of file sac_model_stick.hpp.

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

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

Parameters:
[in]inliersthe data inliers that we want to project on the stick model
[in]model_coefficientsthe *normalized* coefficients of a stick model
[out]projected_pointsthe resultant projected points
[in]copy_data_fieldsset to true if we need to copy the other data fields

Implements pcl::SampleConsensusModel< PointT >.

Definition at line 255 of file sac_model_stick.hpp.

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

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

Parameters:
[in]model_coefficientsthe coefficients of a stick model that we need to compute distances to
[in]thresholda maximum admissible distance threshold for determining the inliers from the outliers
[out]inliersthe resultant model inliers

Implements pcl::SampleConsensusModel< PointT >.

Definition at line 126 of file sac_model_stick.hpp.


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


pcl
Author(s): Open Perception
autogenerated on Mon Oct 6 2014 03:20:09