Public Types | Public Member Functions | Protected Member Functions | Private Attributes
pcl::SampleConsensusModelNormalParallelPlane< PointT, PointNT > Class Template Reference

SampleConsensusModelNormalParallelPlane defines a model for 3D plane segmentation using additional surface normal constraints. Basically this means that checking for inliers will not only involve a "distance to model" criterion, but also an additional "maximum angular deviation" between the plane's normal and the inlier points normals. In addition, the plane normal must lie parallel to an user-specified axis. More...

#include <sac_model_normal_parallel_plane.h>

Inheritance diagram for pcl::SampleConsensusModelNormalParallelPlane< 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
< SampleConsensusModelNormalParallelPlane
Ptr

Public Member Functions

virtual int countWithinDistance (const Eigen::VectorXf &model_coefficients, const double threshold)
 Count all the points which respect the given model coefficients as inliers.
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_PARALLEL_PLANE).
 SampleConsensusModelNormalParallelPlane (const PointCloudConstPtr &cloud)
 Constructor for base SampleConsensusModelNormalParallelPlane.
 SampleConsensusModelNormalParallelPlane (const PointCloudConstPtr &cloud, const std::vector< int > &indices)
 Constructor for base SampleConsensusModelNormalParallelPlane.
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.
void setAxis (const Eigen::Vector3f &ax)
 Set the axis along which we need to search for a plane perpendicular to.
void setDistanceFromOrigin (const double d)
 Set the distance we expect the plane to be from the origin.
void setEpsAngle (const double ea)
 Set the angle epsilon (delta) threshold.
void setEpsDist (const 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::Vector4f axis_
 The axis along which we need to search for a plane perpendicular to.
double cos_angle_
 The cosine of the angle.
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::SampleConsensusModelNormalParallelPlane< PointT, PointNT >

SampleConsensusModelNormalParallelPlane defines a model for 3D plane segmentation using additional surface normal constraints. Basically this means that checking for inliers will not only involve a "distance to model" criterion, but also an additional "maximum angular deviation" between the plane's normal and the inlier points normals. In addition, the plane normal must lie parallel to an user-specified axis.

The model coefficients are defined as:

To set the influence of the surface normals in the inlier estimation process, set the normal weight (0.0-1.0), e.g.:

 SampleConsensusModelNormalPlane<pcl::PointXYZ, pcl::Normal> sac_model;
 ...
 sac_model.setNormalDistanceWeight (0.1);
 ...

In addition, the user can specify more constraints, such as:

Note:
Please remember that you need to specify an angle > 0 in order to activate the axis-angle constraint!
Author:
Radu B. Rusu and Jared Glover and Nico Blodow

Definition at line 85 of file sac_model_normal_parallel_plane.h.


Member Typedef Documentation

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

Reimplemented from pcl::SampleConsensusModelPlane< PointT >.

Definition at line 94 of file sac_model_normal_parallel_plane.h.

Reimplemented from pcl::SampleConsensusModelPlane< PointT >.

Definition at line 96 of file sac_model_normal_parallel_plane.h.

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

Reimplemented from pcl::SampleConsensusModelPlane< PointT >.

Definition at line 95 of file sac_model_normal_parallel_plane.h.

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

Constructor & Destructor Documentation

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

Constructor for base SampleConsensusModelNormalParallelPlane.

Parameters:
[in]cloudthe input point cloud dataset

Definition at line 106 of file sac_model_normal_parallel_plane.h.

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

Constructor for base SampleConsensusModelNormalParallelPlane.

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

Definition at line 118 of file sac_model_normal_parallel_plane.h.


Member Function Documentation

template<typename PointT , typename PointNT >
int pcl::SampleConsensusModelNormalParallelPlane< PointT, PointNT >::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

Reimplemented from pcl::SampleConsensusModelPlane< PointT >.

Definition at line 91 of file sac_model_normal_parallel_plane.hpp.

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

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

Definition at line 134 of file sac_model_normal_parallel_plane.h.

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

Get the distance of the plane from the origin.

Definition at line 155 of file sac_model_normal_parallel_plane.h.

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

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

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

Reimplemented from pcl::SampleConsensusModelPlane< PointT >.

Definition at line 131 of file sac_model_normal_parallel_plane.hpp.

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

Get the angle epsilon (delta) threshold.

Definition at line 145 of file sac_model_normal_parallel_plane.h.

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

Get the distance epsilon (delta) threshold.

Definition at line 165 of file sac_model_normal_parallel_plane.h.

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

Return an unique id for this model (SACMODEL_NORMAL_PARALLEL_PLANE).

Reimplemented from pcl::SampleConsensusModelPlane< PointT >.

Definition at line 197 of file sac_model_normal_parallel_plane.h.

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

Check whether a model is valid given the user constraints.

Parameters:
[in]model_coefficientsthe set of model coefficients

Reimplemented from pcl::SampleConsensusModelPlane< PointT >.

Definition at line 171 of file sac_model_normal_parallel_plane.hpp.

template<typename PointT , typename PointNT >
void pcl::SampleConsensusModelNormalParallelPlane< PointT, PointNT >::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 plane 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

Reimplemented from pcl::SampleConsensusModelPlane< PointT >.

Definition at line 45 of file sac_model_normal_parallel_plane.hpp.

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

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

Parameters:
[in]axthe axis along which we need to search for a plane perpendicular to

Definition at line 130 of file sac_model_normal_parallel_plane.h.

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

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

Parameters:
[in]ddistance from the template plane to the origin

Definition at line 151 of file sac_model_normal_parallel_plane.h.

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

Set the angle epsilon (delta) threshold.

Parameters:
[in]eathe maximum allowed deviation from 90 degrees between the plane normal and the given axis.
Note:
You need to specify an angle > 0 in order to activate the axis-angle constraint!

Definition at line 141 of file sac_model_normal_parallel_plane.h.

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

Set the distance epsilon (delta) threshold.

Parameters:
[in]deltathe maximum allowed deviation from the template distance from the origin

Definition at line 161 of file sac_model_normal_parallel_plane.h.


Member Data Documentation

template<typename PointT, typename PointNT>
Eigen::Vector4f pcl::SampleConsensusModelNormalParallelPlane< PointT, PointNT >::axis_ [private]

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

Definition at line 210 of file sac_model_normal_parallel_plane.h.

template<typename PointT, typename PointNT>
double pcl::SampleConsensusModelNormalParallelPlane< PointT, PointNT >::cos_angle_ [private]

The cosine of the angle.

Definition at line 219 of file sac_model_normal_parallel_plane.h.

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

The distance from the template plane to the origin.

Definition at line 213 of file sac_model_normal_parallel_plane.h.

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

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

Definition at line 216 of file sac_model_normal_parallel_plane.h.

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

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

Definition at line 221 of file sac_model_normal_parallel_plane.h.


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


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