sample_consensus::SAC Class Reference

#include <sac.h>

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

List of all members.

Public Member Functions

virtual void computeCoefficients (std::vector< double > &coefficients)
 Compute the coefficients of the model and return them.
virtual bool computeModel (int debug=0)=0
 Compute the actual model. Pure virtual.
virtual std::vector< int > getInliers ()
 Get a list of the model inliers, found after computeModel ().
sensor_msgs::PointCloud getPointCloud (std::vector< int > indices)
 Return the point cloud representing a set of given indices.
std::set< int > getRandomSamples (sensor_msgs::PointCloud points, std::vector< int > indices, int nr_samples)
 Get a vector of randomly selected indices.
std::set< int > getRandomSamples (sensor_msgs::PointCloud points, int nr_samples)
 Get a set of randomly selected indices.
virtual void projectPointsToModel (const std::vector< int > &indices, const std::vector< double > &model_coefficients, sensor_msgs::PointCloud &projected_points)
 Project a set of given points (using their indices) onto the model and return their projections.
virtual void refineCoefficients (std::vector< double > &refined_coefficients)
 Use Least-Squares optimizations to refine the coefficients of the model, and return them.
virtual int removeInliers ()
 Remove the model inliers from the list of data indices. Returns the number of indices left.
 SAC (SACModel *model)
 Constructor for base SAC.
 SAC ()
 Constructor for base SAC.
virtual void setMaxIterations (int max_iterations)
 Set the maximum number of iterations.
virtual void setProbability (double probability)
 Set the desired probability of choosing at least one sample free from outliers.
virtual void setThreshold (double threshold)
 Set the threshold to model.
virtual ~SAC ()
 Destructor for base SAC.

Protected Attributes

int iterations_
 Total number of internal loop iterations that we've done so far.
int max_iterations_
 Maximum number of iterations before giving up.
double probability_
 Desired probability of choosing at least one sample free from outliers.
SACModelsac_model_
 The underlying data model used (i.e. what is it that we attempt to search for).
double threshold_
 Distance to model threshold.

Detailed Description

Definition at line 39 of file sac.h.


Constructor & Destructor Documentation

sample_consensus::SAC::SAC (  )  [inline]

Constructor for base SAC.

Definition at line 43 of file sac.h.

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

Constructor for base SAC.

Parameters:
model a SAmple Consensus model

Definition at line 52 of file sac.h.

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

Destructor for base SAC.

Definition at line 59 of file sac.h.


Member Function Documentation

virtual void sample_consensus::SAC::computeCoefficients ( std::vector< double > &  coefficients  )  [inline, virtual]

Compute the coefficients of the model and return them.

Definition at line 98 of file sac.h.

virtual bool sample_consensus::SAC::computeModel ( int  debug = 0  )  [pure virtual]

Compute the actual model. Pure virtual.

Implemented in sample_consensus::RANSAC.

virtual std::vector<int> sample_consensus::SAC::getInliers (  )  [inline, virtual]

Get a list of the model inliers, found after computeModel ().

Definition at line 121 of file sac.h.

sensor_msgs::PointCloud SAC::getPointCloud ( std::vector< int >  indices  ) 

Return the point cloud representing a set of given indices.

return the point cloud representing a set of given indices.

Parameters:
indices a set of indices that represent the data that we're interested in

Definition at line 41 of file sac.cpp.

std::set<int> sample_consensus::SAC::getRandomSamples ( sensor_msgs::PointCloud  points,
std::vector< int >  indices,
int  nr_samples 
) [inline]

Get a vector of randomly selected indices.

Note:
Since we return a set, we do not guarantee that we'll return precisely the desired number of samples (ie. nr_samples).
Parameters:
points the point cloud data set to be used (unused)
indices a set of indices that represent the data that we're interested in
nr_samples the desired number of point indices

Definition at line 171 of file sac.h.

std::set<int> sample_consensus::SAC::getRandomSamples ( sensor_msgs::PointCloud  points,
int  nr_samples 
) [inline]

Get a set of randomly selected indices.

Note:
Since we return a set, we do not guarantee that we'll return precisely the desired number of samples (ie. nr_samples).
Parameters:
points the point cloud data set to be used
nr_samples the desired number of point indices

Definition at line 154 of file sac.h.

virtual void sample_consensus::SAC::projectPointsToModel ( const std::vector< int > &  indices,
const std::vector< double > &  model_coefficients,
sensor_msgs::PointCloud &  projected_points 
) [inline, virtual]

Project a set of given points (using their indices) onto the model and return their projections.

Parameters:
indices a set of indices that represent the data that we're interested in
model_coefficients the coefficients of the underlying model
projected_points the resultant projected points

Definition at line 139 of file sac.h.

virtual void sample_consensus::SAC::refineCoefficients ( std::vector< double > &  refined_coefficients  )  [inline, virtual]

Use Least-Squares optimizations to refine the coefficients of the model, and return them.

Parameters:
refit_coefficients the resultant recomputed coefficients after non-linear optimization

Definition at line 109 of file sac.h.

virtual int sample_consensus::SAC::removeInliers (  )  [inline, virtual]

Remove the model inliers from the list of data indices. Returns the number of indices left.

Definition at line 116 of file sac.h.

virtual void sample_consensus::SAC::setMaxIterations ( int  max_iterations  )  [inline, virtual]

Set the maximum number of iterations.

Parameters:
max_iterations maximum number of iterations

Definition at line 76 of file sac.h.

virtual void sample_consensus::SAC::setProbability ( double  probability  )  [inline, virtual]

Set the desired probability of choosing at least one sample free from outliers.

Parameters:
probability the desired probability of choosing at least one sample free from outliers

Definition at line 86 of file sac.h.

virtual void sample_consensus::SAC::setThreshold ( double  threshold  )  [inline, virtual]

Set the threshold to model.

Parameters:
threshold distance to model threshold

Definition at line 66 of file sac.h.


Member Data Documentation

Total number of internal loop iterations that we've done so far.

Definition at line 187 of file sac.h.

Maximum number of iterations before giving up.

Definition at line 190 of file sac.h.

Desired probability of choosing at least one sample free from outliers.

Definition at line 184 of file sac.h.

The underlying data model used (i.e. what is it that we attempt to search for).

Definition at line 181 of file sac.h.

Distance to model threshold.

Definition at line 193 of file sac.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