sample_consensus::SACModelOrientedPlane Class Reference

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

#include <sac_model_oriented_plane.h>

Inheritance diagram for sample_consensus::SACModelOrientedPlane:
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_ORIENTED_PLANE).
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 setEpsAngle (double ea)
 Set the angle epsilon (delta) threshold.

Protected Attributes

geometry_msgs::Point32 axis_
double eps_angle_

Detailed Description

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

Definition at line 45 of file sac_model_oriented_plane.h.


Member Function Documentation

void sample_consensus::SACModelOrientedPlane::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 89 of file sac_model_oriented_plane.cpp.

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

Return an unique id for this model (SACMODEL_ORIENTED_PLANE).

Reimplemented from sample_consensus::SACModelPlane.

Definition at line 72 of file sac_model_oriented_plane.h.

void sample_consensus::SACModelOrientedPlane::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 44 of file sac_model_oriented_plane.cpp.

void sample_consensus::SACModelOrientedPlane::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 54 of file sac_model_oriented_plane.h.

void sample_consensus::SACModelOrientedPlane::setEpsAngle ( double  ea  )  [inline]

Set the angle epsilon (delta) threshold.

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

Definition at line 65 of file sac_model_oriented_plane.h.


Member Data Documentation

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

Definition at line 75 of file sac_model_oriented_plane.h.

Definition at line 76 of file sac_model_oriented_plane.h.


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


door_handle_detector
Author(s): Radu Bogdan Rusu, Marius
autogenerated on Fri Jan 11 09:42:08 2013