33 #ifndef _SAMPLE_CONSENSUS_SACMODEL_H_ 34 #define _SAMPLE_CONSENSUS_SACMODEL_H_ 37 #include <pcl/point_types.h> 62 virtual void getSamples (
int &iterations, std::vector<int> &samples) = 0;
83 virtual void refitModel (
const std::vector<int> &inliers, std::vector<double> &refit_coefficients) = 0;
90 virtual void getDistancesToModel (
const std::vector<double> &model_coefficients, std::vector<double> &distances) = 0;
100 virtual void selectWithinDistance (
const std::vector<double> &model_coefficients,
double threshold, std::vector<int> &inliers) = 0;
108 virtual void projectPoints (
const std::vector<int> &inliers,
const std::vector<double> &model_coefficients, PointCloud &projected_points) = 0;
115 virtual void projectPointsInPlace (
const std::vector<int> &inliers,
const std::vector<double> &model_coefficients) = 0;
134 for (
unsigned int i = 0; i <
cloud_->points.size (); i++)
virtual int removeInliers()
Remove the inliers found from the initial set of given point indices.
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.
std::vector< int > getBestInliers()
Return the best set of inliers found so far for this model.
pcl::PointCloud< pcl::PointXYZ > PointCloud
virtual void projectPoints(const std::vector< int > &inliers, const std::vector< double > &model_coefficients, PointCloud &projected_points)=0
Create a new point cloud with inliers projected onto the model. Pure virtual.
std::vector< int > best_model_
The model found after the last computeModel () as pointcloud indices.
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 the...
std::vector< int > getBestModel()
Return the best model found so far.
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...
PointCloud * cloud_
Holds a pointer to the point cloud data array, since we don't want to copy the whole thing here...
virtual int getModelType()=0
Return an unique id for each type of model employed.
std::vector< int > * getIndices()
Return a pointer to the point cloud data indices.
std::vector< int > best_inliers_
The indices of the points that were chosen as inliers after the last computeModel () call...
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 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...
void setDataSet(PointCloud *cloud, std::vector< int > indices)
Set the dataset and indices.
virtual bool doSamplesVerifyModel(const std::set< int > &indices, double threshold)=0
Verify whether a subset of indices verifies the internal model coefficients. Pure virtual...
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.
virtual ~SACModel()
Destructor for base SACModel.
SACModel(PointCloud cloud)
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.
std::vector< double > getModelCoefficients()
Return the model coefficients of the best model found so far.
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...
PointCloud * getCloud()
Return a pointer to the point cloud data.
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 doi...
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.
void setDataIndices(std::vector< int > indices)
Set the indices.
void setDataSet(PointCloud *cloud)
Set the dataset.