#include <sac.h>
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. | |
SACModel * | sac_model_ |
The underlying data model used (i.e. what is it that we attempt to search for). | |
double | threshold_ |
Distance to model threshold. |
Definition at line 44 of file sac.h.
sample_consensus::SAC::SAC | ( | ) | [inline] |
sample_consensus::SAC::SAC | ( | SACModel * | model | ) | [inline] |
virtual sample_consensus::SAC::~SAC | ( | ) | [inline, virtual] |
virtual void sample_consensus::SAC::computeCoefficients | ( | std::vector< double > & | coefficients | ) | [inline, virtual] |
virtual bool sample_consensus::SAC::computeModel | ( | int | debug = 0 |
) | [pure virtual] |
Compute the actual model. Pure virtual.
Implemented in sample_consensus::MSAC.
virtual std::vector<int> sample_consensus::SAC::getInliers | ( | ) | [inline, virtual] |
sensor_msgs::PointCloud SAC::getPointCloud | ( | std::vector< int > | indices | ) |
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.
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 |
std::set<int> sample_consensus::SAC::getRandomSamples | ( | sensor_msgs::PointCloud | points, | |
int | nr_samples | |||
) | [inline] |
Get a set of randomly selected indices.
points | the point cloud data set to be used | |
nr_samples | the desired number of point indices |
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.
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 |
virtual void sample_consensus::SAC::refineCoefficients | ( | std::vector< double > & | refined_coefficients | ) | [inline, virtual] |
virtual int sample_consensus::SAC::removeInliers | ( | ) | [inline, virtual] |
virtual void sample_consensus::SAC::setMaxIterations | ( | int | max_iterations | ) | [inline, virtual] |
virtual void sample_consensus::SAC::setProbability | ( | double | probability | ) | [inline, virtual] |
virtual void sample_consensus::SAC::setThreshold | ( | double | threshold | ) | [inline, virtual] |
int sample_consensus::SAC::iterations_ [protected] |
int sample_consensus::SAC::max_iterations_ [protected] |
double sample_consensus::SAC::probability_ [protected] |
SACModel* sample_consensus::SAC::sac_model_ [protected] |
double sample_consensus::SAC::threshold_ [protected] |