All Classes Namespaces Files Functions Variables Typedefs Enumerations Properties Friends
Public Types | Public Member Functions | Public Attributes | Protected Member Functions | Private Attributes
pcl::SACModelOrientation< NormalT > Class Template Reference

A Sample Consensus Model class for determining the 2 perpendicular directions to which most normals align. More...

#include <pcl_sac_model_orientation.h>

Inheritance diagram for pcl::SACModelOrientation< NormalT >:
Inheritance graph
[legend]

List of all members.

Public Types

typedef boost::shared_ptr
< const SACModelOrientation
ConstPtr
typedef SampleConsensusModel
< NormalT >::PointCloud 
Normals
typedef SampleConsensusModel
< NormalT >
::PointCloudConstPtr 
NormalsConstPtr
typedef SampleConsensusModel
< NormalT >::PointCloudPtr 
NormalsPtr
typedef boost::shared_ptr
< SACModelOrientation
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 model, compute the model coefficients from these samples and store them internally in model_coefficients_.
int countWithinDistance (const Eigen::VectorXf &model_coefficients, 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, double threshold)
 Verify whether a subset of indices verifies the internal model coefficients.
Eigen::Vector3f getAxis () const
 Get the fixed axis.
void getDistancesToModel (const Eigen::VectorXf &model_coefficients, std::vector< double > &distances)
 Compute all distances from the cloud data to a given model. -- Not needed.
pcl::SacModel getModelType () const
 Return an unique id for each type of model employed.
void getSamples (int &iterations, std::vector< int > &samples)
 Get a random point and return its index.
bool isSampleGood (const std::vector< int > &samples) const
 Check if a sample of indices results in a good sample of points indices. Pure virtual.
void optimizeModelCoefficients (const std::vector< int > &inliers, const Eigen::VectorXf &model_coefficients, Eigen::VectorXf &optimized_coefficients)
void projectPoints (const std::vector< int > &inliers, const Eigen::VectorXf &model_coefficients, Normals &projected_points, bool copy_data_fields=true)
 Create a new point cloud with inliers projected onto the model.
void refitModel (const std::vector< int > &inliers, std::vector< double > &refit_coefficients)
 Recompute the model coefficients using the given inlier set and return them to the user. Pure virtual.
 SACModelOrientation (const NormalsConstPtr &cloud)
 Constructor for base SACModelOrientation.
 SACModelOrientation (const NormalsConstPtr &cloud, const std::vector< int > &indices)
 Constructor for base SACModelOrientation.
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.
void setAxis (Eigen::Vector3f axis)
 Specify the fixed "up" axis (the sides will be perpendicular to it).

Public Attributes

Eigen::Vector3f axis_
 The fixed axis (the sides will be perpendicular to it).

Protected Member Functions

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

Private Attributes

std::vector< intback_indices_
std::vector< intfront_indices_
KdTreeFLANN< NormalT >::Ptr kdtree_
 Index of the nx channel (the x component of the normal vector). The next indices are assumed to be that of ny and nz!
std::vector< intleft_indices_
std::vector< float > points_sqr_distances_
std::vector< intright_indices_

Detailed Description

template<typename NormalT>
class pcl::SACModelOrientation< NormalT >

A Sample Consensus Model class for determining the 2 perpendicular directions to which most normals align.

Definition at line 61 of file pcl_sac_model_orientation.h.


Member Typedef Documentation

template<typename NormalT >
typedef boost::shared_ptr<const SACModelOrientation> pcl::SACModelOrientation< NormalT >::ConstPtr

Reimplemented from pcl::SampleConsensusModel< NormalT >.

Definition at line 72 of file pcl_sac_model_orientation.h.

Definition at line 67 of file pcl_sac_model_orientation.h.

Definition at line 69 of file pcl_sac_model_orientation.h.

Definition at line 68 of file pcl_sac_model_orientation.h.

template<typename NormalT >
typedef boost::shared_ptr<SACModelOrientation> pcl::SACModelOrientation< NormalT >::Ptr

Reimplemented from pcl::SampleConsensusModel< NormalT >.

Definition at line 71 of file pcl_sac_model_orientation.h.


Constructor & Destructor Documentation

template<typename NormalT >
pcl::SACModelOrientation< NormalT >::SACModelOrientation ( const NormalsConstPtr cloud) [inline]

Constructor for base SACModelOrientation.

Parameters:
cloudthe input point cloud dataset containing the normals

Definition at line 82 of file pcl_sac_model_orientation.h.

template<typename NormalT >
pcl::SACModelOrientation< NormalT >::SACModelOrientation ( const NormalsConstPtr cloud,
const std::vector< int > &  indices 
) [inline]

Constructor for base SACModelOrientation.

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

Definition at line 95 of file pcl_sac_model_orientation.h.


Member Function Documentation

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

Check whether the given index samples can form a valid model, compute the model coefficients from these samples and store them internally in model_coefficients_.

Note:
Model coefficients are the normal of the sample point (and it's index for testModelCoefficients)
Parameters:
samplesthe point indices found as possible good candidates for creating a valid model

Implements pcl::SampleConsensusModel< NormalT >.

Definition at line 90 of file pcl_sac_model_orientation.hpp.

template<typename NormalT >
int pcl::SACModelOrientation< NormalT >::countWithinDistance ( const Eigen::VectorXf &  model_coefficients,
double  threshold 
) [inline, 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]thresholda maximum admissible distance threshold for determining the inliers from the outliers
Returns:
the resultant number of inliers

Implements pcl::SampleConsensusModel< NormalT >.

Definition at line 159 of file pcl_sac_model_orientation.h.

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

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

Parameters:
indicesthe data indices that need to be tested against the model (each element is an index of indices_)
thresholda maximum admissible distance threshold for determining the inliers from the outliers

Implements pcl::SampleConsensusModel< NormalT >.

Definition at line 180 of file pcl_sac_model_orientation.h.

template<typename NormalT >
Eigen::Vector3f pcl::SACModelOrientation< NormalT >::getAxis ( ) const [inline]

Get the fixed axis.

Definition at line 109 of file pcl_sac_model_orientation.h.

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

Compute all distances from the cloud data to a given model. -- Not needed.

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

Implements pcl::SampleConsensusModel< NormalT >.

Definition at line 139 of file pcl_sac_model_orientation.h.

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

Return an unique id for each type of model employed.

Implements pcl::SampleConsensusModel< NormalT >.

Definition at line 192 of file pcl_sac_model_orientation.h.

template<typename NormalT >
void pcl::SACModelOrientation< NormalT >::getSamples ( int iterations,
std::vector< int > &  samples 
)

Get a random point and return its index.

Parameters:
iterationsthe internal number of iterations used by SAC methods (incremented at samplings that can not produce a model) -- Not needed.
samplesthe resultant model samples

: we get an index of the indices_ vector because normals_ has only those elements!

Reimplemented from pcl::SampleConsensusModel< NormalT >.

Definition at line 69 of file pcl_sac_model_orientation.hpp.

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

Check whether a model is valid given the user constraints.

Parameters:
model_coefficientsthe set of model coefficients

Implements pcl::SampleConsensusModel< NormalT >.

Definition at line 206 of file pcl_sac_model_orientation.h.

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

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

Parameters:
samplesthe resultant index samples

Implements pcl::SampleConsensusModel< NormalT >.

Definition at line 236 of file pcl_sac_model_orientation.hpp.

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

Implements pcl::SampleConsensusModel< NormalT >.

Definition at line 194 of file pcl_sac_model_orientation.h.

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

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

Parameters:
inliersthe data inliers that we want to project on the model (each element is an index of indices_)
model_coefficientsthe coefficients of a model
projected_pointsthe resultant projected points

Definition at line 172 of file pcl_sac_model_orientation.h.

template<typename NormalT >
void pcl::SACModelOrientation< NormalT >::refitModel ( const std::vector< int > &  inliers,
std::vector< double > &  refit_coefficients 
)

Recompute the model coefficients using the given inlier set and return them to the user. Pure virtual.

Note:
: These are the coefficients of the model after refinement (eg. after a least-squares optimization)
Parameters:
inliersthe data inliers found as supporting the model (each element is an index of indices_)
refit_coefficientsthe resultant recomputed coefficients (has -1 as source index in refit_coefficients[3] at failures)

inliers is a list of indices of the indices_ array! normal_ contains only the elements listed in the indices_ array!

Definition at line 110 of file pcl_sac_model_orientation.hpp.

template<typename NormalT >
void pcl::SACModelOrientation< NormalT >::selectWithinDistance ( const Eigen::VectorXf &  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 model that we need to compute distances to
thresholda maximum admissible distance threshold for determining the inliers from the outliers
inliersthe resultant model inliers (each element is an index of indices_)
Note:
: To get the refined inliers of a model, use: refined_coeff = refitModel (...); selectWithinDistance (refined_coeff, threshold);

: inliers are actually indexes in the indices_ array! TODO still true?

Implements pcl::SampleConsensusModel< NormalT >.

Definition at line 170 of file pcl_sac_model_orientation.hpp.

template<typename NormalT >
void pcl::SACModelOrientation< NormalT >::setAxis ( Eigen::Vector3f  axis) [inline]

Specify the fixed "up" axis (the sides will be perpendicular to it).

Parameters:
axisa direction in 3D space.

Definition at line 105 of file pcl_sac_model_orientation.h.


Member Data Documentation

template<typename NormalT >
Eigen::Vector3f pcl::SACModelOrientation< NormalT >::axis_

The fixed axis (the sides will be perpendicular to it).

Definition at line 76 of file pcl_sac_model_orientation.h.

template<typename NormalT >
std::vector<int> pcl::SACModelOrientation< NormalT >::back_indices_ [private]

Definition at line 222 of file pcl_sac_model_orientation.h.

template<typename NormalT >
std::vector<int> pcl::SACModelOrientation< NormalT >::front_indices_ [private]

Definition at line 221 of file pcl_sac_model_orientation.h.

template<typename NormalT >
KdTreeFLANN<NormalT>::Ptr pcl::SACModelOrientation< NormalT >::kdtree_ [private]

Index of the nx channel (the x component of the normal vector). The next indices are assumed to be that of ny and nz!

Kd-Tree for searching in normal space.

Definition at line 220 of file pcl_sac_model_orientation.h.

template<typename NormalT >
std::vector<int> pcl::SACModelOrientation< NormalT >::left_indices_ [private]

Definition at line 223 of file pcl_sac_model_orientation.h.

template<typename NormalT >
std::vector<float> pcl::SACModelOrientation< NormalT >::points_sqr_distances_ [private]

Definition at line 225 of file pcl_sac_model_orientation.h.

template<typename NormalT >
std::vector<int> pcl::SACModelOrientation< NormalT >::right_indices_ [private]

Definition at line 224 of file pcl_sac_model_orientation.h.


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


pcl_ias_sample_consensus
Author(s): Nico Blodow, Dejan Pangercic, Zoltan-Csaba MArton
autogenerated on Sun Oct 6 2013 12:02:37