sample_consensus::SACModel Class Reference

#include <sac_model.h>

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

List of all members.

Public Member Functions

virtual bool computeModelCoefficients (const std::vector< int > &samples)=0
 Check whether the given index samples can form a valid model, compute the model coefficients from these samples and store them internally in model_coefficients_. Pure virtual.
virtual bool doSamplesVerifyModel (const std::set< int > &indices, double threshold)=0
 Verify whether a subset of indices verifies the internal model coefficients. Pure virtual.
std::vector< int > getBestInliers ()
 Return the best set of inliers found so far for this model.
std::vector< int > getBestModel ()
 Return the best model found so far.
sensor_msgs::PointCloud * getCloud ()
 Return a pointer to the point cloud data.
virtual void getDistancesToModel (const std::vector< double > &model_coefficients, std::vector< double > &distances)=0
 Compute all distances from the cloud data to a given model. Pure virtual.
std::vector< int > * getIndices ()
 Return a pointer to the point cloud data indices.
std::vector< double > getModelCoefficients ()
 Return the model coefficients of the best model found so far.
virtual int getModelType ()=0
 Return an unique id for each type of model employed.
virtual void getSamples (int &iterations, std::vector< int > &samples)=0
 Get a set of random data samples and return them as point indices. Pure virtual.
virtual void projectPoints (const std::vector< int > &inliers, const std::vector< double > &model_coefficients, sensor_msgs::PointCloud &projected_points)=0
 Create a new point cloud with inliers projected onto the model. Pure virtual.
virtual void projectPointsInPlace (const std::vector< int > &inliers, const std::vector< double > &model_coefficients)=0
 Project inliers (in place) onto the given model. Pure virtual.
virtual void refitModel (const std::vector< int > &inliers, std::vector< double > &refit_coefficients)=0
 Recompute the model coefficients using the given inlier set and return them to the user. Pure virtual.
virtual int removeInliers ()
 Remove the inliers found from the initial set of given point indices.
 SACModel (sensor_msgs::PointCloud cloud)
 SACModel ()
 Constructor for base SACModel.
virtual void selectWithinDistance (const std::vector< double > &model_coefficients, double threshold, std::vector< int > &inliers)=0
 Select all the points which respect the given model coefficients as inliers. Pure virtual.
void setBestInliers (const std::vector< int > &best_inliers)
 Set the best set of inliers. Used by SAC methods. Do not call this except if you know what you're doing.
void setBestModel (std::vector< int > best_model)
 Set the best model. Used by SAC methods. Do not call this except if you know what you're doing.
void setDataIndices (std::vector< int > indices)
 Set the indices.
void setDataSet (sensor_msgs::PointCloud *cloud, std::vector< int > indices)
 Set the dataset and indices.
void setDataSet (sensor_msgs::PointCloud *cloud)
 Set the dataset.
virtual bool testModelCoefficients (const std::vector< double > &model_coefficients)=0
 Test whether the given model coefficients are valid given the input point cloud data. Pure virtual.
virtual ~SACModel ()
 Destructor for base SACModel.

Protected Attributes

std::vector< int > best_inliers_
 The indices of the points that were chosen as inliers after the last computeModel () call.
std::vector< int > best_model_
 The model found after the last computeModel () as pointcloud indices.
sensor_msgs::PointCloud * cloud_
 Holds a pointer to the point cloud data array, since we don't want to copy the whole thing here.
std::vector< int > indices_
 The list of internal point indices used.
std::vector< double > model_coefficients_
 The coefficients of our model computed directly from the best samples found.

Detailed Description

Definition at line 43 of file sac_model.h.


Constructor & Destructor Documentation

sample_consensus::SACModel::SACModel (  )  [inline]

Constructor for base SACModel.

Definition at line 48 of file sac_model.h.

sample_consensus::SACModel::SACModel ( sensor_msgs::PointCloud  cloud  )  [inline]

Definition at line 49 of file sac_model.h.

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

Destructor for base SACModel.

Definition at line 53 of file sac_model.h.


Member Function Documentation

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

Check whether the given index samples can form a valid model, compute the model coefficients from these samples and store them internally in model_coefficients_. Pure virtual.

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

Implemented in sample_consensus::SACModelLine.

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

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

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

Implemented in sample_consensus::SACModelLine.

std::vector<int> sample_consensus::SACModel::getBestInliers (  )  [inline]

Return the best set of inliers found so far for this model.

Definition at line 165 of file sac_model.h.

std::vector<int> sample_consensus::SACModel::getBestModel (  )  [inline]

Return the best model found so far.

Definition at line 174 of file sac_model.h.

sensor_msgs::PointCloud* sample_consensus::SACModel::getCloud (  )  [inline]

Return a pointer to the point cloud data.

Definition at line 181 of file sac_model.h.

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

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

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

Implemented in sample_consensus::SACModelLine.

std::vector<int>* sample_consensus::SACModel::getIndices (  )  [inline]

Return a pointer to the point cloud data indices.

Definition at line 184 of file sac_model.h.

std::vector<double> sample_consensus::SACModel::getModelCoefficients (  )  [inline]

Return the model coefficients of the best model found so far.

Definition at line 178 of file sac_model.h.

virtual int sample_consensus::SACModel::getModelType (  )  [pure virtual]

Return an unique id for each type of model employed.

Implemented in sample_consensus::SACModelLine.

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

Get a set of random data samples and return them as point indices. Pure virtual.

Parameters:
iterations the internal number of iterations used by SAC methods
samples the resultant model samples

Implemented in sample_consensus::SACModelLine.

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

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

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

Implemented in sample_consensus::SACModelLine.

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

Project inliers (in place) onto the given model. Pure virtual.

Parameters:
inliers the data inliers that we want to project on the model
model_coefficients the coefficients of a model

Implemented in sample_consensus::SACModelLine.

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

Recompute the model coefficients using the given inlier set and return them to the user. Pure virtual.

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

Implemented in sample_consensus::SACModelLine.

int sample_consensus::SACModel::removeInliers (  )  [virtual]

Remove the inliers found from the initial set of given point indices.

Definition at line 41 of file sac_model.cpp.

virtual void sample_consensus::SACModel::selectWithinDistance ( const std::vector< double > &  model_coefficients,
double  threshold,
std::vector< int > &  inliers 
) [pure virtual]

Select all the points which respect the given model coefficients as inliers. Pure virtual.

Parameters:
model_coefficients the coefficients of a 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);

Implemented in sample_consensus::SACModelLine.

void sample_consensus::SACModel::setBestInliers ( const std::vector< int > &  best_inliers  )  [inline]

Set the best set of inliers. Used by SAC methods. Do not call this except if you know what you're doing.

Parameters:
best_inliers the set of inliers for the best model

Definition at line 161 of file sac_model.h.

void sample_consensus::SACModel::setBestModel ( std::vector< int >  best_model  )  [inline]

Set the best model. Used by SAC methods. Do not call this except if you know what you're doing.

Parameters:
best_model the best model found so far

Definition at line 170 of file sac_model.h.

void sample_consensus::SACModel::setDataIndices ( std::vector< int >  indices  )  [inline]

Set the indices.

Parameters:
indices the point indices used

Definition at line 148 of file sac_model.h.

void sample_consensus::SACModel::setDataSet ( sensor_msgs::PointCloud *  cloud,
std::vector< int >  indices 
) [inline]

Set the dataset and indices.

Parameters:
cloud the data set to be used
indices the point indices used

Definition at line 140 of file sac_model.h.

void sample_consensus::SACModel::setDataSet ( sensor_msgs::PointCloud *  cloud  )  [inline]

Set the dataset.

Parameters:
cloud the data set to be used

Definition at line 127 of file sac_model.h.

virtual bool sample_consensus::SACModel::testModelCoefficients ( const std::vector< double > &  model_coefficients  )  [pure virtual]

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

Parameters:
model_coefficients the model coefficients that need to be tested

Implemented in sample_consensus::SACModelLine.


Member Data Documentation

std::vector<int> sample_consensus::SACModel::best_inliers_ [protected]

The indices of the points that were chosen as inliers after the last computeModel () call.

Definition at line 200 of file sac_model.h.

std::vector<int> sample_consensus::SACModel::best_model_ [protected]

The model found after the last computeModel () as pointcloud indices.

Definition at line 198 of file sac_model.h.

sensor_msgs::PointCloud* sample_consensus::SACModel::cloud_ [protected]

Holds a pointer to the point cloud data array, since we don't want to copy the whole thing here.

Definition at line 189 of file sac_model.h.

std::vector<int> sample_consensus::SACModel::indices_ [protected]

The list of internal point indices used.

Definition at line 192 of file sac_model.h.

std::vector<double> sample_consensus::SACModel::model_coefficients_ [protected]

The coefficients of our model computed directly from the best samples found.

Definition at line 195 of file sac_model.h.


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


semantic_point_annotator
Author(s): Radu Bogdan Rusu
autogenerated on Fri Jan 11 09:12:48 2013