sample_consensus::SACModelSphere Class Reference

A Sample Consensus Model class for sphere segmentation. More...

#include <sac_model_sphere.h>

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

List of all members.

Public Member Functions

virtual bool computeModelCoefficients (const std::vector< int > &samples)
 Check whether the given index samples can form a valid sphere model, compute the model coefficients from these samples and store them internally in model_coefficients_. The sphere coefficients are: x, y, z, R.
virtual bool doSamplesVerifyModel (const std::set< int > &indices, double threshold)
 Verify whether a subset of indices verifies the internal sphere model coefficients.
virtual void getDistancesToModel (const std::vector< double > &model_coefficients, std::vector< double > &distances)
 Compute all distances from the cloud data to a given sphere model.
virtual int getModelType ()
 Return an unique id for this model (SACMODEL_SPHERE).
virtual void getSamples (int &iterations, std::vector< int > &samples)
 Get 4 random points (3 non-collinear) as data samples and return them as point indices.
virtual void projectPoints (const std::vector< int > &inliers, const std::vector< double > &model_coefficients, sensor_msgs::PointCloud &projected_points)
 Create a new point cloud with inliers projected onto the sphere model.
virtual void projectPointsInPlace (const std::vector< int > &inliers, const std::vector< double > &model_coefficients)
 Project inliers (in place) onto the given sphere model.
virtual void refitModel (const std::vector< int > &inliers, std::vector< double > &refit_coefficients)
 Recompute the sphere coefficients using the given inlier set and return them to the user.
 SACModelSphere ()
 Constructor for base SACModelSphere.
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.
bool testModelCoefficients (const std::vector< double > &model_coefficients)
 Test whether the given model coefficients are valid given the input point cloud data.
virtual ~SACModelSphere ()
 Destructor for base SACModelSphere.

Static Public 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

const std::vector< int > * tmp_inliers_
 temporary pointer to a list of given indices for refitModel ()

Detailed Description

A Sample Consensus Model class for sphere segmentation.

Definition at line 46 of file sac_model_sphere.h.


Constructor & Destructor Documentation

sample_consensus::SACModelSphere::SACModelSphere (  )  [inline]

Constructor for base SACModelSphere.

Definition at line 51 of file sac_model_sphere.h.

virtual sample_consensus::SACModelSphere::~SACModelSphere (  )  [inline, virtual]

Destructor for base SACModelSphere.

Definition at line 55 of file sac_model_sphere.h.


Member Function Documentation

bool sample_consensus::SACModelSphere::computeModelCoefficients ( const std::vector< int > &  samples  )  [virtual]

Check whether the given index samples can form a valid sphere model, compute the model coefficients from these samples and store them internally in model_coefficients_. The sphere coefficients are: x, y, z, R.

Parameters:
samples the point indices found as possible good candidates for creating a valid model

Implements sample_consensus::SACModel.

Definition at line 214 of file sac_model_sphere.cpp.

bool sample_consensus::SACModelSphere::doSamplesVerifyModel ( const std::set< int > &  indices,
double  threshold 
) [virtual]

Verify whether a subset of indices verifies the internal sphere model coefficients.

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

Implements sample_consensus::SACModel.

Definition at line 362 of file sac_model_sphere.cpp.

int sample_consensus::SACModelSphere::functionToOptimize ( void *  p,
int  m,
int  n,
const double *  x,
double *  fvec,
int  iflag 
) [static]

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 339 of file sac_model_sphere.cpp.

void sample_consensus::SACModelSphere::getDistancesToModel ( const std::vector< double > &  model_coefficients,
std::vector< double > &  distances 
) [virtual]

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

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

Implements sample_consensus::SACModel.

Definition at line 160 of file sac_model_sphere.cpp.

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

Return an unique id for this model (SACMODEL_SPHERE).

Implements sample_consensus::SACModel.

Definition at line 81 of file sac_model_sphere.h.

void sample_consensus::SACModelSphere::getSamples ( int &  iterations,
std::vector< int > &  samples 
) [virtual]

Get 4 random points (3 non-collinear) 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!
Two different points could be enough in theory, to infere some sort of a center and a radius, but in practice, we might end up with a lot of points which are just 'close' to one another. Therefore we have two options: a) use normal information (good but I wouldn't rely on it in extremely noisy point clouds, no matter what) b) get two more points and uniquely identify a sphere in space (3 unique points define a circle)

Implements sample_consensus::SACModel.

Definition at line 47 of file sac_model_sphere.cpp.

void sample_consensus::SACModelSphere::projectPoints ( const std::vector< int > &  inliers,
const std::vector< double > &  model_coefficients,
sensor_msgs::PointCloud &  projected_points 
) [virtual]

Create a new point cloud with inliers projected onto the sphere model.

Parameters:
inliers the data inliers that we want to project on the sphere model
model_coefficients the coefficients of a sphere model
projected_points the resultant projected points
Todo:
implement this.

Implements sample_consensus::SACModel.

Definition at line 189 of file sac_model_sphere.cpp.

void sample_consensus::SACModelSphere::projectPointsInPlace ( const std::vector< int > &  inliers,
const std::vector< double > &  model_coefficients 
) [virtual]

Project inliers (in place) onto the given sphere model.

Parameters:
inliers the data inliers that we want to project on the sphere model
model_coefficients the coefficients of a sphere model
Todo:
implement this.

Implements sample_consensus::SACModel.

Definition at line 203 of file sac_model_sphere.cpp.

void sample_consensus::SACModelSphere::refitModel ( const std::vector< int > &  inliers,
std::vector< double > &  refit_coefficients 
) [virtual]

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

Note:
: these are the coefficients of the sphere model after refinement (eg. after SVD)
Parameters:
inliers the data inliers found as supporting the model
refit_coefficients the resultant recomputed coefficients after non-linear optimization

Implements sample_consensus::SACModel.

Definition at line 279 of file sac_model_sphere.cpp.

void sample_consensus::SACModelSphere::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 sphere 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
Note:
: To get the refined inliers of a model, use: ANNpoint refined_coeff = refitModel (...); selectWithinDistance (refined_coeff, threshold);

Implements sample_consensus::SACModel.

Definition at line 124 of file sac_model_sphere.cpp.

bool sample_consensus::SACModelSphere::testModelCoefficients ( const std::vector< double > &  model_coefficients  )  [inline, virtual]

Test whether the given model coefficients are valid given the input point cloud data.

Parameters:
model_coefficients the model coefficients that need to be tested
Todo:
implement this

Implements sample_consensus::SACModel.

Definition at line 64 of file sac_model_sphere.h.


Member Data Documentation

const std::vector<int>* sample_consensus::SACModelSphere::tmp_inliers_ [private]

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

Definition at line 85 of file sac_model_sphere.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