sample_consensus::SACModelNormalPlane Class Reference

A Sample Consensus Model class for normal 3D plane segmentation. More...

#include <sac_model_normal_plane.h>

Inheritance diagram for sample_consensus::SACModelNormalPlane:
Inheritance graph
[legend]

List of all members.

Public Member Functions

virtual void getDistancesToModel (const std::vector< double > &model_coefficients, std::vector< double > &distances)
 Compute all distances from the cloud data to a given plane model.
virtual int getModelType ()
 Return an unique id for this model (SACMODEL_NORMAL_PLANE).
 SACModelNormalPlane ()
virtual void selectWithinDistance (const std::vector< double > &model_coefficients, double threshold, std::vector< int > &inliers)
 Select all the points which respect the given model coefficients as inliers.
void setAxis (const geometry_msgs::Point32 &ax)
 Set the axis along which we need to search for a plane perpendicular to.
void setDist (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.
void setNormalDistanceWeight (double w)
 Set the normal angular distance weight.

Protected Attributes

geometry_msgs::Point32 axis_
double dist_
double eps_angle_
double eps_dist_
double normal_distance_weight_

Detailed Description

A Sample Consensus Model class for normal 3D plane segmentation.

Definition at line 45 of file sac_model_normal_plane.h.


Constructor & Destructor Documentation

sample_consensus::SACModelNormalPlane::SACModelNormalPlane (  )  [inline]

Definition at line 50 of file sac_model_normal_plane.h.


Member Function Documentation

void sample_consensus::SACModelNormalPlane::getDistancesToModel ( const std::vector< double > &  model_coefficients,
std::vector< double > &  distances 
) [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 sample_consensus::SACModelPlane.

Definition at line 144 of file sac_model_normal_plane.cpp.

virtual int sample_consensus::SACModelNormalPlane::getModelType (  )  [inline, virtual]

Return an unique id for this model (SACMODEL_NORMAL_PLANE).

Reimplemented from sample_consensus::SACModelPlane.

Definition at line 97 of file sac_model_normal_plane.h.

void sample_consensus::SACModelNormalPlane::selectWithinDistance ( const std::vector< double > &  model_coefficients,
double  threshold,
std::vector< int > &  inliers 
) [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
Note:
: To get the refined inliers of a model, use: ANNpoint refined_coeff = refitModel (...); selectWithinDistance (refined_coeff, threshold);

Reimplemented from sample_consensus::SACModelPlane.

Definition at line 58 of file sac_model_normal_plane.cpp.

void sample_consensus::SACModelNormalPlane::setAxis ( const geometry_msgs::Point32 &  ax  )  [inline]

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

Parameters:
ax a pointer to the axis.

Definition at line 67 of file sac_model_normal_plane.h.

void sample_consensus::SACModelNormalPlane::setDist ( 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 84 of file sac_model_normal_plane.h.

void sample_consensus::SACModelNormalPlane::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 78 of file sac_model_normal_plane.h.

void sample_consensus::SACModelNormalPlane::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 90 of file sac_model_normal_plane.h.

void sample_consensus::SACModelNormalPlane::setNormalDistanceWeight ( double  w  )  [inline]

Set the normal angular distance weight.

Parameters:
w the relative weight (between 0 and 1) to give to the angular distance (0 to pi/2) between point normals and the plane normal. (The Euclidean distance will have weight 1-w.)

Definition at line 61 of file sac_model_normal_plane.h.


Member Data Documentation

geometry_msgs::Point32 sample_consensus::SACModelNormalPlane::axis_ [protected]

Definition at line 101 of file sac_model_normal_plane.h.

Definition at line 102 of file sac_model_normal_plane.h.

Definition at line 103 of file sac_model_normal_plane.h.

Definition at line 104 of file sac_model_normal_plane.h.

Definition at line 100 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


stereo_wall_detection
Author(s): Radu Bogdan Rusu
autogenerated on Fri Jan 11 09:37:23 2013