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

SampleConsensusModelNormalPlane defines a model for 3D plane segmentation using additional surface normal constraints. More...

#include <sac_model_normal_plane.h>

Inheritance diagram for pcl::SampleConsensusModelNormalPlane< PointT, PointNT >:
Inheritance graph
[legend]

List of all members.

Public Types

typedef SampleConsensusModel
< PointT >::PointCloud 
PointCloud
typedef SampleConsensusModel
< PointT >::PointCloudConstPtr 
PointCloudConstPtr
typedef
SampleConsensusModelFromNormals
< PointT, PointNT >
::PointCloudNConstPtr 
PointCloudNConstPtr
typedef
SampleConsensusModelFromNormals
< PointT, PointNT >
::PointCloudNPtr 
PointCloudNPtr
typedef SampleConsensusModel
< PointT >::PointCloudPtr 
PointCloudPtr
typedef boost::shared_ptr
< SampleConsensusModelNormalPlane
Ptr

Public Member Functions

Eigen::Vector3f getAxis ()
 Get the axis along which we need to search for a plane perpendicular to.
double getDistanceFromOrigin ()
 Get the distance of the plane from the origin.
void getDistancesToModel (const Eigen::VectorXf &model_coefficients, std::vector< double > &distances)
 Compute all distances from the cloud data to a given plane model.
double getEpsAngle ()
 Get the angle epsilon (delta) threshold.
double getEpsDist ()
 Get the distance epsilon (delta) threshold.
pcl::SacModel getModelType () const
 Return an unique id for this model (SACMODEL_NORMAL_PLANE).
 SampleConsensusModelNormalPlane (const PointCloudConstPtr &cloud, const std::vector< int > &indices)
 Constructor for base SampleConsensusModelNormalPlane.
 SampleConsensusModelNormalPlane (const PointCloudConstPtr &cloud)
 Constructor for base SampleConsensusModelNormalPlane.
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 plane perpendicular to.
void setDistanceFromOrigin (double d)
 Set the distance we expect the plane to be from the origin.
void setEpsAngle (double ea)
 Set the angle epsilon (delta) threshold.
void setEpsDist (double delta)
 Set the distance epsilon (delta) threshold.

Protected Member Functions

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

Private Attributes

Eigen::Vector3f axis_
 The axis along which we need to search for a plane perpendicular to.
double distance_from_origin_
 The distance from the template plane to the origin.
double eps_angle_
 The maximum allowed difference between the plane normal and the given axis.
double eps_dist_
 The maximum allowed deviation from the template distance from the origin.

Detailed Description

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

SampleConsensusModelNormalPlane defines a model for 3D plane segmentation using additional surface normal constraints.

Author:
Radu Bogdan Rusu and Jared Glover

Definition at line 58 of file sac_model_normal_plane.h.


Member Typedef Documentation

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

Reimplemented from pcl::SampleConsensusModelPlane< PointT >.

Definition at line 67 of file sac_model_normal_plane.h.

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

Reimplemented from pcl::SampleConsensusModelPlane< PointT >.

Definition at line 69 of file sac_model_normal_plane.h.

template<typename PointT, typename PointNT>
typedef SampleConsensusModelFromNormals<PointT, PointNT>::PointCloudNConstPtr pcl::SampleConsensusModelNormalPlane< PointT, PointNT >::PointCloudNConstPtr
template<typename PointT, typename PointNT>
typedef SampleConsensusModelFromNormals<PointT, PointNT>::PointCloudNPtr pcl::SampleConsensusModelNormalPlane< PointT, PointNT >::PointCloudNPtr
template<typename PointT, typename PointNT>
typedef SampleConsensusModel<PointT>::PointCloudPtr pcl::SampleConsensusModelNormalPlane< PointT, PointNT >::PointCloudPtr

Reimplemented from pcl::SampleConsensusModelPlane< PointT >.

Definition at line 68 of file sac_model_normal_plane.h.

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

Constructor & Destructor Documentation

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

Constructor for base SampleConsensusModelNormalPlane.

Parameters:
cloud the input point cloud dataset

Definition at line 79 of file sac_model_normal_plane.h.

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

Constructor for base SampleConsensusModelNormalPlane.

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

Definition at line 89 of file sac_model_normal_plane.h.


Member Function Documentation

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

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

Definition at line 101 of file sac_model_normal_plane.h.

template<typename PointT, typename PointNT>
double pcl::SampleConsensusModelNormalPlane< PointT, PointNT >::getDistanceFromOrigin (  )  [inline]

Get the distance of the plane from the origin.

Definition at line 117 of file sac_model_normal_plane.h.

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

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

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

Reimplemented from pcl::SampleConsensusModelPlane< PointT >.

Definition at line 109 of file sac_model_normal_plane.hpp.

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

Get the angle epsilon (delta) threshold.

Definition at line 109 of file sac_model_normal_plane.h.

template<typename PointT, typename PointNT>
double pcl::SampleConsensusModelNormalPlane< PointT, PointNT >::getEpsDist (  )  [inline]

Get the distance epsilon (delta) threshold.

Definition at line 125 of file sac_model_normal_plane.h.

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

Return an unique id for this model (SACMODEL_NORMAL_PLANE).

Reimplemented from pcl::SampleConsensusModelPlane< PointT >.

Definition at line 141 of file sac_model_normal_plane.h.

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

Reimplemented from pcl::SampleConsensusModelPlane< PointT >.

Definition at line 160 of file sac_model_normal_plane.hpp.

template<typename PointT , typename PointNT >
void pcl::SampleConsensusModelNormalPlane< 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 plane model that we need to compute distances to
inliers the resultant model inliers
threshold a maximum admissible distance threshold for determining the inliers from the outliers

Reimplemented from pcl::SampleConsensusModelPlane< PointT >.

Definition at line 50 of file sac_model_normal_plane.hpp.

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

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

Parameters:
ax the axis along which we need to search for a plane perpendicular to

Definition at line 98 of file sac_model_normal_plane.h.

template<typename PointT, typename PointNT>
void pcl::SampleConsensusModelNormalPlane< PointT, PointNT >::setDistanceFromOrigin ( double  d  )  [inline]

Set the distance we expect the plane to be from the origin.

Parameters:
d distance from the template plane to the origin

Definition at line 114 of file sac_model_normal_plane.h.

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

Set the angle epsilon (delta) threshold.

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

Definition at line 106 of file sac_model_normal_plane.h.

template<typename PointT, typename PointNT>
void pcl::SampleConsensusModelNormalPlane< PointT, PointNT >::setEpsDist ( double  delta  )  [inline]

Set the distance epsilon (delta) threshold.

Parameters:
delta the maximum allowed deviation from the template distance from the origin

Definition at line 122 of file sac_model_normal_plane.h.


Member Data Documentation

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

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

Definition at line 153 of file sac_model_normal_plane.h.

template<typename PointT, typename PointNT>
double pcl::SampleConsensusModelNormalPlane< PointT, PointNT >::distance_from_origin_ [private]

The distance from the template plane to the origin.

Definition at line 156 of file sac_model_normal_plane.h.

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

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

Definition at line 159 of file sac_model_normal_plane.h.

template<typename PointT, typename PointNT>
double pcl::SampleConsensusModelNormalPlane< PointT, PointNT >::eps_dist_ [private]

The maximum allowed deviation from the template distance from the origin.

Definition at line 162 of file sac_model_normal_plane.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