pcl::SampleConsensusModelCylinder< PointT, PointNT > Class Template Reference

SampleConsensusModelCylinder defines a model for 3D cylinder segmentation. More...

#include <sac_model_cylinder.h>

Inheritance diagram for pcl::SampleConsensusModelCylinder< PointT, PointNT >:
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
< SampleConsensusModelCylinder
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 cylinder model, compute the model coefficients from these samples and store them in model_coefficients. The cylinder coefficients are: point_on_axis, axis_direction, cylinder_radius_R.
bool doSamplesVerifyModel (const std::set< int > &indices, const Eigen::VectorXf &model_coefficients, double threshold)
 Verify whether a subset of indices verifies the given cylinder model coefficients.
Eigen::Vector3f getAxis ()
 Get the axis along which we need to search for a cylinder direction.
void getDistancesToModel (const Eigen::VectorXf &model_coefficients, std::vector< double > &distances)
 Compute all distances from the cloud data to a given cylinder model.
double getEpsAngle ()
 Get the angle epsilon (delta) threshold.
pcl::SacModel getModelType () const
 Return an unique id for this model (SACMODEL_CYLINDER).
void getSamples (int &iterations, std::vector< int > &samples)
 Get 2 random points with their normals 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 cylinder 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 cylinder model.
 SampleConsensusModelCylinder (const PointCloudConstPtr &cloud, const std::vector< int > &indices)
 Constructor for base SampleConsensusModelCylinder.
 SampleConsensusModelCylinder (const PointCloudConstPtr &cloud)
 Constructor for base SampleConsensusModelCylinder.
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 (const Eigen::Vector3f &ax)
 Set the axis along which we need to search for a cylinder direction.
void setEpsAngle (double ea)
 Set the angle epsilon (delta) threshold.

Protected Member Functions

std::string getName () const
 Get a string representation of the name of this class.
bool isModelValid (const Eigen::VectorXf &model_coefficients)
 Check whether a model is valid given the user constraints.
double pointToLineDistance (const Eigen::Vector4f &pt, const Eigen::VectorXf &model_coefficients)
 Get the distance from a point to a line (represented by a point and a direction).
void projectPointToCylinder (const Eigen::Vector4f &pt, const Eigen::VectorXf &model_coefficients, Eigen::Vector4f &pt_proj)
 Project a point onto a cylinder given by its model coefficients (point_on_axis, axis_direction, cylinder_radius_R).
void projectPointToLine (const Eigen::Vector4f &pt, const Eigen::Vector4f &line_pt, const Eigen::Vector4f &line_dir, Eigen::Vector4f &pt_proj)
 Project a point onto a line given by a point and a direction vector.

Static Private Member Functions

static int functionToOptimize (void *p, int m, int n, const double *x, double *fvec, int iflag)
 Cost function to be minimized.

Private Attributes

Eigen::Vector3f axis_
 The axis along which we need to search for a plane perpendicular to.
double eps_angle_
 The maximum allowed difference between the plane normal and the given axis.
const std::vector< int > * tmp_inliers_
 temporary pointer to a list of given indices for optimizeModelCoefficients ()
boost::mutex tmp_mutex_
 Temporary boost mutex for tmp_inliers_.

Static Private Attributes

static const int MAX_ITERATIONS_COLLINEAR = 1000
 Define the maximum number of iterations for collinearity checks.

Detailed Description

template<typename PointT, typename PointNT>
class pcl::SampleConsensusModelCylinder< PointT, PointNT >

SampleConsensusModelCylinder defines a model for 3D cylinder segmentation.

Author:
Radu Bogdan Rusu

Definition at line 54 of file sac_model_cylinder.h.


Member Typedef Documentation

template<typename PointT, typename PointNT>
typedef SampleConsensusModel<PointT>::PointCloud pcl::SampleConsensusModelCylinder< PointT, PointNT >::PointCloud

Reimplemented from pcl::SampleConsensusModel< PointT >.

Definition at line 64 of file sac_model_cylinder.h.

template<typename PointT, typename PointNT>
typedef SampleConsensusModel<PointT>::PointCloudConstPtr pcl::SampleConsensusModelCylinder< PointT, PointNT >::PointCloudConstPtr

Reimplemented from pcl::SampleConsensusModel< PointT >.

Definition at line 66 of file sac_model_cylinder.h.

template<typename PointT, typename PointNT>
typedef SampleConsensusModel<PointT>::PointCloudPtr pcl::SampleConsensusModelCylinder< PointT, PointNT >::PointCloudPtr

Reimplemented from pcl::SampleConsensusModel< PointT >.

Definition at line 65 of file sac_model_cylinder.h.

template<typename PointT, typename PointNT>
typedef boost::shared_ptr<SampleConsensusModelCylinder> pcl::SampleConsensusModelCylinder< PointT, PointNT >::Ptr

Reimplemented from pcl::SampleConsensusModel< PointT >.

Definition at line 68 of file sac_model_cylinder.h.


Constructor & Destructor Documentation

template<typename PointT, typename PointNT>
pcl::SampleConsensusModelCylinder< PointT, PointNT >::SampleConsensusModelCylinder ( const PointCloudConstPtr cloud  )  [inline]

Constructor for base SampleConsensusModelCylinder.

Parameters:
cloud the input point cloud dataset

Definition at line 73 of file sac_model_cylinder.h.

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

Constructor for base SampleConsensusModelCylinder.

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

Definition at line 82 of file sac_model_cylinder.h.


Member Function Documentation

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

Check whether the given index samples can form a valid cylinder model, compute the model coefficients from these samples and store them in model_coefficients. The cylinder coefficients are: point_on_axis, axis_direction, cylinder_radius_R.

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 96 of file sac_model_cylinder.hpp.

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

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

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

Implements pcl::SampleConsensusModel< PointT >.

Definition at line 453 of file sac_model_cylinder.hpp.

template<typename PointT , typename PointNT >
int pcl::SampleConsensusModelCylinder< PointT, PointNT >::functionToOptimize ( void *  p,
int  m,
int  n,
const double *  x,
double *  fvec,
int  iflag 
) [inline, static, private]

Cost function to be minimized.

Parameters:
p a pointer to our data structure array
m the number of functions
n the number of variables
x a pointer to the variables array
fvec a pointer to the resultant functions evaluations
iflag set to -1 inside the function to terminate execution

Definition at line 341 of file sac_model_cylinder.hpp.

template<typename PointT, typename PointNT>
Eigen::Vector3f pcl::SampleConsensusModelCylinder< PointT, PointNT >::getAxis (  )  [inline]

Get the axis along which we need to search for a cylinder direction.

Definition at line 101 of file sac_model_cylinder.h.

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

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

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

Implements pcl::SampleConsensusModel< PointT >.

Definition at line 161 of file sac_model_cylinder.hpp.

template<typename PointT, typename PointNT>
double pcl::SampleConsensusModelCylinder< PointT, PointNT >::getEpsAngle (  )  [inline]

Get the angle epsilon (delta) threshold.

Definition at line 93 of file sac_model_cylinder.h.

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

Return an unique id for this model (SACMODEL_CYLINDER).

Implements pcl::SampleConsensusModel< PointT >.

Definition at line 157 of file sac_model_cylinder.h.

template<typename PointT, typename PointNT>
std::string pcl::SampleConsensusModelCylinder< PointT, PointNT >::getName (  )  const [inline, protected]

Get a string representation of the name of this class.

Definition at line 190 of file sac_model_cylinder.h.

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

Get 2 random points with their normals 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 51 of file sac_model_cylinder.hpp.

template<typename PointT , typename PointNT >
bool pcl::SampleConsensusModelCylinder< PointT, PointNT >::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 >.

Definition at line 519 of file sac_model_cylinder.hpp.

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

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

Note:
: these are the coefficients of the cylinder model after refinement (eg. after SVD)
Parameters:
inliers the data inliers found as supporting the model
model_coefficients the initial guess for the optimization
optimized_coefficients the resultant recomputed coefficients after non-linear optimization

Implements pcl::SampleConsensusModel< PointT >.

Definition at line 277 of file sac_model_cylinder.hpp.

template<typename PointT , typename PointNT >
double pcl::SampleConsensusModelCylinder< PointT, PointNT >::pointToLineDistance ( const Eigen::Vector4f &  pt,
const Eigen::VectorXf &  model_coefficients 
) [inline, protected]

Get the distance from a point to a line (represented by a point and a direction).

Parameters:
pt a point
model_coefficients the line coefficients (a point on the line, line direction)

Definition at line 482 of file sac_model_cylinder.hpp.

template<typename PointT , typename PointNT >
void pcl::SampleConsensusModelCylinder< PointT, PointNT >::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 cylinder model.

Parameters:
inliers the data inliers that we want to project on the cylinder model
model_coefficients the coefficients of a cylinder model
projected_points the resultant projected points
copy_data_fields set to true if we need to copy the other data fields
Todo:
implement this.
Parameters:
inliers the data inliers that we want to project on the cylinder model
model_coefficients the coefficients of a cylinder model
projected_points the resultant projected points
copy_data_fields set to true if we need to copy the other data fields
Todo:
implement this.

Implements pcl::SampleConsensusModel< PointT >.

Definition at line 368 of file sac_model_cylinder.hpp.

template<typename PointT , typename PointNT >
void pcl::SampleConsensusModelCylinder< PointT, PointNT >::projectPointToCylinder ( const Eigen::Vector4f &  pt,
const Eigen::VectorXf &  model_coefficients,
Eigen::Vector4f &  pt_proj 
) [inline, protected]

Project a point onto a cylinder given by its model coefficients (point_on_axis, axis_direction, cylinder_radius_R).

Parameters:
pt the input point to project
model_coefficients the coefficients of the cylinder (point_on_axis, axis_direction, cylinder_radius_R)
pt_proj the resultant projected point

Definition at line 498 of file sac_model_cylinder.hpp.

template<typename PointT, typename PointNT>
void pcl::SampleConsensusModelCylinder< PointT, PointNT >::projectPointToLine ( const Eigen::Vector4f &  pt,
const Eigen::Vector4f &  line_pt,
const Eigen::Vector4f &  line_dir,
Eigen::Vector4f &  pt_proj 
) [inline, protected]

Project a point onto a line given by a point and a direction vector.

Parameters:
pt the input point to project
line_pt the point on the line (make sure that line_pt[3] = 0 as there are no internal checks!)
line_dir the direction of the line (make sure that line_dir[3] = 0 as there are no internal checks!)
pt_proj the resultant projected point

Definition at line 173 of file sac_model_cylinder.h.

template<typename PointT , typename PointNT >
void pcl::SampleConsensusModelCylinder< PointT, PointNT >::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 cylinder 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 >.

Definition at line 216 of file sac_model_cylinder.hpp.

template<typename PointT, typename PointNT>
void pcl::SampleConsensusModelCylinder< PointT, PointNT >::setAxis ( const Eigen::Vector3f &  ax  )  [inline]

Set the axis along which we need to search for a cylinder direction.

Parameters:
ax the axis along which we need to search for a cylinder direction

Definition at line 98 of file sac_model_cylinder.h.

template<typename PointT, typename PointNT>
void pcl::SampleConsensusModelCylinder< PointT, PointNT >::setEpsAngle ( double  ea  )  [inline]

Set the angle epsilon (delta) threshold.

Parameters:
ea the maximum allowed difference between the cyilinder axis and the given axis.

Definition at line 90 of file sac_model_cylinder.h.


Member Data Documentation

template<typename PointT, typename PointNT>
Eigen::Vector3f pcl::SampleConsensusModelCylinder< PointT, PointNT >::axis_ [private]

The axis along which we need to search for a plane perpendicular to.

Definition at line 200 of file sac_model_cylinder.h.

template<typename PointT, typename PointNT>
double pcl::SampleConsensusModelCylinder< PointT, PointNT >::eps_angle_ [private]

The maximum allowed difference between the plane normal and the given axis.

Definition at line 203 of file sac_model_cylinder.h.

template<typename PointT, typename PointNT>
const int pcl::SampleConsensusModelCylinder< PointT, PointNT >::MAX_ITERATIONS_COLLINEAR = 1000 [static, private]

Define the maximum number of iterations for collinearity checks.

Definition at line 212 of file sac_model_cylinder.h.

template<typename PointT, typename PointNT>
const std::vector<int>* pcl::SampleConsensusModelCylinder< PointT, PointNT >::tmp_inliers_ [private]

temporary pointer to a list of given indices for optimizeModelCoefficients ()

Definition at line 209 of file sac_model_cylinder.h.

template<typename PointT, typename PointNT>
boost::mutex pcl::SampleConsensusModelCylinder< PointT, PointNT >::tmp_mutex_ [private]

Temporary boost mutex for tmp_inliers_.

Definition at line 206 of file sac_model_cylinder.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