SampleConsensusModel represents the base model class. All sample consensus models must inherit from this class. More...
#include <sac_model.h>
Public Types | |
typedef boost::shared_ptr < const SampleConsensusModel > | ConstPtr |
typedef pcl::PointCloud< PointT > | PointCloud |
typedef pcl::PointCloud < PointT >::ConstPtr | PointCloudConstPtr |
typedef pcl::PointCloud < PointT >::Ptr | PointCloudPtr |
typedef boost::shared_ptr < SampleConsensusModel > | Ptr |
typedef pcl::search::Search < PointT >::Ptr | SearchPtr |
Public Member Functions | |
virtual bool | computeModelCoefficients (const std::vector< int > &samples, Eigen::VectorXf &model_coefficients)=0 |
Check whether the given index samples can form a valid model, compute the model coefficients from these samples and store them in model_coefficients. Pure virtual. | |
double | computeVariance (const std::vector< double > &error_sqr_dists) |
Compute the variance of the errors to the model. | |
double | computeVariance () |
Compute the variance of the errors to the model from the internally estimated vector of distances. The model must be computed first (or at least selectWithinDistance must be called). | |
virtual int | countWithinDistance (const Eigen::VectorXf &model_coefficients, const double threshold)=0 |
Count all the points which respect the given model coefficients as inliers. Pure virtual. | |
virtual bool | doSamplesVerifyModel (const std::set< int > &indices, const Eigen::VectorXf &model_coefficients, const double threshold)=0 |
Verify whether a subset of indices verifies a given set of model coefficients. Pure virtual. | |
virtual void | getDistancesToModel (const Eigen::VectorXf &model_coefficients, std::vector< double > &distances)=0 |
Compute all distances from the cloud data to a given model. Pure virtual. | |
boost::shared_ptr< std::vector < int > > | getIndices () const |
Get a pointer to the vector of indices used. | |
PointCloudConstPtr | getInputCloud () const |
Get a pointer to the input point cloud dataset. | |
virtual SacModel | getModelType () const =0 |
Return an unique id for each type of model employed. | |
void | getRadiusLimits (double &min_radius, double &max_radius) |
Get the minimum and maximum allowable radius limits for the model as set by the user. | |
virtual void | getSamples (int &iterations, std::vector< int > &samples) |
Get a set of random data samples and return them as point indices. | |
unsigned int | getSampleSize () const |
Return the size of a sample from which a model is computed. | |
void | getSamplesMaxDist (double &radius) |
Get maximum distance allowed when drawing random samples. | |
virtual void | optimizeModelCoefficients (const std::vector< int > &inliers, const Eigen::VectorXf &model_coefficients, Eigen::VectorXf &optimized_coefficients)=0 |
Recompute the model coefficients using the given inlier set and return them to the user. Pure virtual. | |
virtual void | projectPoints (const std::vector< int > &inliers, const Eigen::VectorXf &model_coefficients, PointCloud &projected_points, bool copy_data_fields=true)=0 |
Create a new point cloud with inliers projected onto the model. Pure virtual. | |
SampleConsensusModel (const PointCloudConstPtr &cloud, bool random=false) | |
Constructor for base SampleConsensusModel. | |
SampleConsensusModel (const PointCloudConstPtr &cloud, const std::vector< int > &indices, bool random=false) | |
Constructor for base SampleConsensusModel. | |
virtual void | selectWithinDistance (const Eigen::VectorXf &model_coefficients, const double threshold, std::vector< int > &inliers)=0 |
Select all the points which respect the given model coefficients as inliers. Pure virtual. | |
void | setIndices (const boost::shared_ptr< std::vector< int > > &indices) |
Provide a pointer to the vector of indices that represents the input data. | |
void | setIndices (const std::vector< int > &indices) |
Provide the vector of indices that represents the input data. | |
virtual void | setInputCloud (const PointCloudConstPtr &cloud) |
Provide a pointer to the input dataset. | |
void | setRadiusLimits (const double &min_radius, const double &max_radius) |
Set the minimum and maximum allowable radius limits for the model (applicable to models that estimate a radius) | |
void | setSamplesMaxDist (const double &radius, SearchPtr search) |
Set the maximum distance allowed when drawing random samples. | |
virtual | ~SampleConsensusModel () |
Destructor for base SampleConsensusModel. | |
Protected Member Functions | |
void | drawIndexSample (std::vector< int > &sample) |
Fills a sample array with random samples from the indices_ vector. | |
void | drawIndexSampleRadius (std::vector< int > &sample) |
Fills a sample array with one random sample from the indices_ vector and other random samples that are closer than samples_radius_. | |
virtual bool | isModelValid (const Eigen::VectorXf &model_coefficients)=0 |
Check whether a model is valid given the user constraints. | |
virtual bool | isSampleGood (const std::vector< int > &samples) const =0 |
Check if a sample of indices results in a good sample of points indices. Pure virtual. | |
int | rnd () |
Boost-based random number generator. | |
SampleConsensusModel (bool random=false) | |
Empty constructor for base SampleConsensusModel. | |
Protected Attributes | |
std::vector< double > | error_sqr_dists_ |
A vector holding the distances to the computed model. Used internally. | |
boost::shared_ptr< std::vector < int > > | indices_ |
A pointer to the vector of point indices to use. | |
PointCloudConstPtr | input_ |
A boost shared pointer to the point cloud data array. | |
double | radius_max_ |
double | radius_min_ |
The minimum and maximum radius limits for the model. Applicable to all models that estimate a radius. | |
boost::mt19937 | rng_alg_ |
Boost-based random number generator algorithm. | |
boost::shared_ptr < boost::uniform_int<> > | rng_dist_ |
Boost-based random number generator distribution. | |
boost::shared_ptr < boost::variate_generator < boost::mt19937 &, boost::uniform_int<> > > | rng_gen_ |
Boost-based random number generator. | |
double | samples_radius_ |
The maximum distance of subsequent samples from the first (radius search) | |
SearchPtr | samples_radius_search_ |
The search object for picking subsequent samples using radius search. | |
std::vector< int > | shuffled_indices_ |
Static Protected Attributes | |
static const unsigned int | max_sample_checks_ = 1000 |
Friends | |
class | ProgressiveSampleConsensus< PointT > |
SampleConsensusModel represents the base model class. All sample consensus models must inherit from this class.
Definition at line 66 of file sac_model.h.
typedef boost::shared_ptr<const SampleConsensusModel> pcl::SampleConsensusModel< PointT >::ConstPtr |
Reimplemented in pcl::SampleConsensusModelCircle3D< PointT >, and pcl::SampleConsensusModelRegistration2D< PointT >.
Definition at line 75 of file sac_model.h.
typedef pcl::PointCloud<PointT> pcl::SampleConsensusModel< PointT >::PointCloud |
Reimplemented in pcl::SampleConsensusModelPlane< PointT >, pcl::SampleConsensusModelNormalParallelPlane< PointT, PointNT >, pcl::SampleConsensusModelNormalPlane< PointT, PointNT >, pcl::SampleConsensusModelNormalSphere< PointT, PointNT >, pcl::SampleConsensusModelCone< PointT, PointNT >, pcl::SampleConsensusModelCylinder< PointT, PointNT >, pcl::SampleConsensusModelPerpendicularPlane< PointT >, pcl::SampleConsensusModelStick< PointT >, pcl::SampleConsensusModelLine< PointT >, pcl::SampleConsensusModelCircle2D< PointT >, pcl::SampleConsensusModelCircle3D< PointT >, pcl::SampleConsensusModelParallelPlane< PointT >, pcl::SampleConsensusModelSphere< PointT >, pcl::SampleConsensusModelParallelLine< PointT >, pcl::SampleConsensusModelRegistration< PointT >, and pcl::SampleConsensusModelRegistration2D< PointT >.
Definition at line 69 of file sac_model.h.
typedef pcl::PointCloud<PointT>::ConstPtr pcl::SampleConsensusModel< PointT >::PointCloudConstPtr |
Reimplemented in pcl::SampleConsensusModelPlane< PointT >, pcl::SampleConsensusModelNormalParallelPlane< PointT, PointNT >, pcl::SampleConsensusModelNormalPlane< PointT, PointNT >, pcl::SampleConsensusModelNormalSphere< PointT, PointNT >, pcl::SampleConsensusModelCone< PointT, PointNT >, pcl::SampleConsensusModelCylinder< PointT, PointNT >, pcl::SampleConsensusModelPerpendicularPlane< PointT >, pcl::SampleConsensusModelStick< PointT >, pcl::SampleConsensusModelLine< PointT >, pcl::SampleConsensusModelCircle2D< PointT >, pcl::SampleConsensusModelCircle3D< PointT >, pcl::SampleConsensusModelParallelPlane< PointT >, pcl::SampleConsensusModelSphere< PointT >, pcl::SampleConsensusModelParallelLine< PointT >, pcl::SampleConsensusModelRegistration< PointT >, and pcl::SampleConsensusModelRegistration2D< PointT >.
Definition at line 70 of file sac_model.h.
typedef pcl::PointCloud<PointT>::Ptr pcl::SampleConsensusModel< PointT >::PointCloudPtr |
Reimplemented in pcl::SampleConsensusModelPlane< PointT >, pcl::SampleConsensusModelNormalParallelPlane< PointT, PointNT >, pcl::SampleConsensusModelNormalPlane< PointT, PointNT >, pcl::SampleConsensusModelNormalSphere< PointT, PointNT >, pcl::SampleConsensusModelCone< PointT, PointNT >, pcl::SampleConsensusModelCylinder< PointT, PointNT >, pcl::SampleConsensusModelPerpendicularPlane< PointT >, pcl::SampleConsensusModelStick< PointT >, pcl::SampleConsensusModelLine< PointT >, pcl::SampleConsensusModelCircle2D< PointT >, pcl::SampleConsensusModelCircle3D< PointT >, pcl::SampleConsensusModelParallelPlane< PointT >, pcl::SampleConsensusModelSphere< PointT >, pcl::SampleConsensusModelParallelLine< PointT >, pcl::SampleConsensusModelRegistration< PointT >, and pcl::SampleConsensusModelRegistration2D< PointT >.
Definition at line 71 of file sac_model.h.
typedef boost::shared_ptr<SampleConsensusModel> pcl::SampleConsensusModel< PointT >::Ptr |
Reimplemented in pcl::SampleConsensusModelPlane< PointT >, pcl::SampleConsensusModelNormalParallelPlane< PointT, PointNT >, pcl::SampleConsensusModelNormalPlane< PointT, PointNT >, pcl::SampleConsensusModelNormalSphere< PointT, PointNT >, pcl::SampleConsensusModelCone< PointT, PointNT >, pcl::SampleConsensusModelCylinder< PointT, PointNT >, pcl::SampleConsensusModelPerpendicularPlane< PointT >, pcl::SampleConsensusModelStick< PointT >, pcl::SampleConsensusModelLine< PointT >, pcl::SampleConsensusModelCircle2D< PointT >, pcl::SampleConsensusModelCircle3D< PointT >, pcl::SampleConsensusModelParallelPlane< PointT >, pcl::SampleConsensusModelSphere< PointT >, pcl::SampleConsensusModelParallelLine< PointT >, pcl::SampleConsensusModelRegistration< PointT >, and pcl::SampleConsensusModelRegistration2D< PointT >.
Definition at line 74 of file sac_model.h.
typedef pcl::search::Search<PointT>::Ptr pcl::SampleConsensusModel< PointT >::SearchPtr |
Definition at line 72 of file sac_model.h.
pcl::SampleConsensusModel< PointT >::SampleConsensusModel | ( | bool | random = false | ) | [inline, protected] |
Empty constructor for base SampleConsensusModel.
[in] | random | if true set the random seed to the current time, else set to 12345 (default: false) |
Definition at line 81 of file sac_model.h.
pcl::SampleConsensusModel< PointT >::SampleConsensusModel | ( | const PointCloudConstPtr & | cloud, |
bool | random = false |
||
) | [inline] |
Constructor for base SampleConsensusModel.
[in] | cloud | the input point cloud dataset |
[in] | random | if true set the random seed to the current time, else set to 12345 (default: false) |
Definition at line 108 of file sac_model.h.
pcl::SampleConsensusModel< PointT >::SampleConsensusModel | ( | const PointCloudConstPtr & | cloud, |
const std::vector< int > & | indices, | ||
bool | random = false |
||
) | [inline] |
Constructor for base SampleConsensusModel.
[in] | cloud | the input point cloud dataset |
[in] | indices | a vector of point indices to be used from cloud |
[in] | random | if true set the random seed to the current time, else set to 12345 (default: false) |
Definition at line 138 of file sac_model.h.
virtual pcl::SampleConsensusModel< PointT >::~SampleConsensusModel | ( | ) | [inline, virtual] |
Destructor for base SampleConsensusModel.
Definition at line 170 of file sac_model.h.
virtual bool pcl::SampleConsensusModel< PointT >::computeModelCoefficients | ( | const std::vector< int > & | samples, |
Eigen::VectorXf & | model_coefficients | ||
) | [pure virtual] |
Check whether the given index samples can form a valid model, compute the model coefficients from these samples and store them in model_coefficients. Pure virtual.
[in] | samples | the point indices found as possible good candidates for creating a valid model |
[out] | model_coefficients | the computed model coefficients |
Implemented in pcl::SampleConsensusModelCone< PointT, PointNT >, pcl::SampleConsensusModelPlane< PointT >, pcl::SampleConsensusModelCylinder< PointT, PointNT >, pcl::SampleConsensusModelRegistration< PointT >, pcl::SampleConsensusModelSphere< PointT >, pcl::SampleConsensusModelCircle2D< PointT >, pcl::SampleConsensusModelCircle3D< PointT >, pcl::SampleConsensusModelStick< PointT >, and pcl::SampleConsensusModelLine< PointT >.
double pcl::SampleConsensusModel< PointT >::computeVariance | ( | const std::vector< double > & | error_sqr_dists | ) | [inline] |
Compute the variance of the errors to the model.
[in] | error_sqr_dists | a vector holding the distances |
Definition at line 413 of file sac_model.h.
double pcl::SampleConsensusModel< PointT >::computeVariance | ( | ) | [inline] |
Compute the variance of the errors to the model from the internally estimated vector of distances. The model must be computed first (or at least selectWithinDistance must be called).
Definition at line 426 of file sac_model.h.
virtual int pcl::SampleConsensusModel< PointT >::countWithinDistance | ( | const Eigen::VectorXf & | model_coefficients, |
const double | threshold | ||
) | [pure virtual] |
Count all the points which respect the given model coefficients as inliers. Pure virtual.
[in] | model_coefficients | the coefficients of a model that we need to compute distances to |
[in] | threshold | a maximum admissible distance threshold for determining the inliers from the outliers |
Implemented in pcl::SampleConsensusModelCone< PointT, PointNT >, pcl::SampleConsensusModelPlane< PointT >, pcl::SampleConsensusModelNormalParallelPlane< PointT, PointNT >, pcl::SampleConsensusModelCylinder< PointT, PointNT >, pcl::SampleConsensusModelRegistration< PointT >, pcl::SampleConsensusModelSphere< PointT >, pcl::SampleConsensusModelCircle2D< PointT >, pcl::SampleConsensusModelCircle3D< PointT >, pcl::SampleConsensusModelPerpendicularPlane< PointT >, pcl::SampleConsensusModelParallelPlane< PointT >, pcl::SampleConsensusModelNormalPlane< PointT, PointNT >, pcl::SampleConsensusModelParallelLine< PointT >, pcl::SampleConsensusModelStick< PointT >, pcl::SampleConsensusModelNormalSphere< PointT, PointNT >, pcl::SampleConsensusModelLine< PointT >, and pcl::SampleConsensusModelRegistration2D< PointT >.
virtual bool pcl::SampleConsensusModel< PointT >::doSamplesVerifyModel | ( | const std::set< int > & | indices, |
const Eigen::VectorXf & | model_coefficients, | ||
const double | threshold | ||
) | [pure virtual] |
Verify whether a subset of indices verifies a given set of model coefficients. Pure virtual.
[in] | indices | the data indices that need to be tested against the model |
[in] | model_coefficients | the set of model coefficients |
[in] | threshold | a maximum admissible distance threshold for determining the inliers from the outliers |
Implemented in pcl::SampleConsensusModelCone< PointT, PointNT >, pcl::SampleConsensusModelPlane< PointT >, pcl::SampleConsensusModelCylinder< PointT, PointNT >, pcl::SampleConsensusModelRegistration< PointT >, pcl::SampleConsensusModelSphere< PointT >, pcl::SampleConsensusModelCircle2D< PointT >, pcl::SampleConsensusModelCircle3D< PointT >, pcl::SampleConsensusModelStick< PointT >, and pcl::SampleConsensusModelLine< PointT >.
void pcl::SampleConsensusModel< PointT >::drawIndexSample | ( | std::vector< int > & | sample | ) | [inline, protected] |
Fills a sample array with random samples from the indices_ vector.
[out] | sample | the set of indices of target_ to analyze |
Definition at line 441 of file sac_model.h.
void pcl::SampleConsensusModel< PointT >::drawIndexSampleRadius | ( | std::vector< int > & | sample | ) | [inline, protected] |
Fills a sample array with one random sample from the indices_ vector and other random samples that are closer than samples_radius_.
[out] | sample | the set of indices of target_ to analyze |
Definition at line 458 of file sac_model.h.
virtual void pcl::SampleConsensusModel< PointT >::getDistancesToModel | ( | const Eigen::VectorXf & | model_coefficients, |
std::vector< double > & | distances | ||
) | [pure virtual] |
Compute all distances from the cloud data to a given model. Pure virtual.
[in] | model_coefficients | the coefficients of a model that we need to compute distances to |
[out] | distances | the resultant estimated distances |
Implemented in pcl::SampleConsensusModelNormalParallelPlane< PointT, PointNT >, pcl::SampleConsensusModelCone< PointT, PointNT >, pcl::SampleConsensusModelPlane< PointT >, pcl::SampleConsensusModelCylinder< PointT, PointNT >, pcl::SampleConsensusModelRegistration< PointT >, pcl::SampleConsensusModelPerpendicularPlane< PointT >, pcl::SampleConsensusModelParallelPlane< PointT >, pcl::SampleConsensusModelNormalPlane< PointT, PointNT >, pcl::SampleConsensusModelParallelLine< PointT >, pcl::SampleConsensusModelNormalSphere< PointT, PointNT >, pcl::SampleConsensusModelSphere< PointT >, pcl::SampleConsensusModelCircle2D< PointT >, pcl::SampleConsensusModelCircle3D< PointT >, pcl::SampleConsensusModelStick< PointT >, pcl::SampleConsensusModelLine< PointT >, and pcl::SampleConsensusModelRegistration2D< PointT >.
boost::shared_ptr<std::vector<int> > pcl::SampleConsensusModel< PointT >::getIndices | ( | ) | const [inline] |
Get a pointer to the vector of indices used.
Definition at line 345 of file sac_model.h.
PointCloudConstPtr pcl::SampleConsensusModel< PointT >::getInputCloud | ( | ) | const [inline] |
Get a pointer to the input point cloud dataset.
Definition at line 321 of file sac_model.h.
virtual SacModel pcl::SampleConsensusModel< PointT >::getModelType | ( | ) | const [pure virtual] |
Return an unique id for each type of model employed.
Implemented in pcl::SampleConsensusModelCone< PointT, PointNT >, pcl::SampleConsensusModelPlane< PointT >, pcl::SampleConsensusModelCylinder< PointT, PointNT >, pcl::SampleConsensusModelNormalParallelPlane< PointT, PointNT >, pcl::SampleConsensusModelRegistration< PointT >, pcl::SampleConsensusModelSphere< PointT >, pcl::SampleConsensusModelCircle2D< PointT >, pcl::SampleConsensusModelCircle3D< PointT >, pcl::SampleConsensusModelStick< PointT >, pcl::SampleConsensusModelLine< PointT >, pcl::SampleConsensusModelPerpendicularPlane< PointT >, pcl::SampleConsensusModelParallelPlane< PointT >, pcl::SampleConsensusModelNormalPlane< PointT, PointNT >, pcl::SampleConsensusModelParallelLine< PointT >, and pcl::SampleConsensusModelNormalSphere< PointT, PointNT >.
void pcl::SampleConsensusModel< PointT >::getRadiusLimits | ( | double & | min_radius, |
double & | max_radius | ||
) | [inline] |
Get the minimum and maximum allowable radius limits for the model as set by the user.
[out] | min_radius | the resultant minimum radius model |
[out] | max_radius | the resultant maximum radius model |
Definition at line 381 of file sac_model.h.
virtual void pcl::SampleConsensusModel< PointT >::getSamples | ( | int & | iterations, |
std::vector< int > & | samples | ||
) | [inline, virtual] |
Get a set of random data samples and return them as point indices.
[out] | iterations | the internal number of iterations used by SAC methods |
[out] | samples | the resultant model samples |
Definition at line 178 of file sac_model.h.
unsigned int pcl::SampleConsensusModel< PointT >::getSampleSize | ( | ) | const [inline] |
Return the size of a sample from which a model is computed.
Definition at line 353 of file sac_model.h.
void pcl::SampleConsensusModel< PointT >::getSamplesMaxDist | ( | double & | radius | ) | [inline] |
Get maximum distance allowed when drawing random samples.
[out] | radius | the maximum distance (L2 norm) |
Definition at line 402 of file sac_model.h.
virtual bool pcl::SampleConsensusModel< PointT >::isModelValid | ( | const Eigen::VectorXf & | model_coefficients | ) | [inline, protected, pure virtual] |
Check whether a model is valid given the user constraints.
[in] | model_coefficients | the set of model coefficients |
Implemented in pcl::SampleConsensusModelCone< PointT, PointNT >, pcl::SampleConsensusModelCylinder< PointT, PointNT >, pcl::SampleConsensusModelPlane< PointT >, pcl::SampleConsensusModelNormalParallelPlane< PointT, PointNT >, pcl::SampleConsensusModelRegistration< PointT >, pcl::SampleConsensusModelSphere< PointT >, pcl::SampleConsensusModelCircle2D< PointT >, pcl::SampleConsensusModelCircle3D< PointT >, pcl::SampleConsensusModelStick< PointT >, pcl::SampleConsensusModelLine< PointT >, pcl::SampleConsensusModelPerpendicularPlane< PointT >, pcl::SampleConsensusModelParallelPlane< PointT >, pcl::SampleConsensusModelParallelLine< PointT >, and pcl::SampleConsensusModelNormalSphere< PointT, PointNT >.
virtual bool pcl::SampleConsensusModel< PointT >::isSampleGood | ( | const std::vector< int > & | samples | ) | const [protected, pure virtual] |
Check if a sample of indices results in a good sample of points indices. Pure virtual.
[in] | samples | the resultant index samples |
Implemented in pcl::SampleConsensusModelCone< PointT, PointNT >, pcl::SampleConsensusModelCylinder< PointT, PointNT >, pcl::SampleConsensusModelPlane< PointT >, pcl::SampleConsensusModelRegistration< PointT >, pcl::SampleConsensusModelSphere< PointT >, pcl::SampleConsensusModelCircle2D< PointT >, pcl::SampleConsensusModelCircle3D< PointT >, pcl::SampleConsensusModelStick< PointT >, pcl::SampleConsensusModelLine< PointT >, and pcl::SampleConsensusModelRegistration2D< PointT >.
virtual void pcl::SampleConsensusModel< PointT >::optimizeModelCoefficients | ( | const std::vector< int > & | inliers, |
const Eigen::VectorXf & | model_coefficients, | ||
Eigen::VectorXf & | optimized_coefficients | ||
) | [pure virtual] |
Recompute the model coefficients using the given inlier set and return them to the user. Pure virtual.
[in] | inliers | the data inliers supporting the model |
[in] | model_coefficients | the initial guess for the model coefficients |
[out] | optimized_coefficients | the resultant recomputed coefficients after non-linear optimization |
Implemented in pcl::SampleConsensusModelCone< PointT, PointNT >, pcl::SampleConsensusModelPlane< PointT >, pcl::SampleConsensusModelCylinder< PointT, PointNT >, pcl::SampleConsensusModelRegistration< PointT >, pcl::SampleConsensusModelSphere< PointT >, pcl::SampleConsensusModelCircle2D< PointT >, pcl::SampleConsensusModelCircle3D< PointT >, pcl::SampleConsensusModelStick< PointT >, and pcl::SampleConsensusModelLine< PointT >.
virtual void pcl::SampleConsensusModel< PointT >::projectPoints | ( | const std::vector< int > & | inliers, |
const Eigen::VectorXf & | model_coefficients, | ||
PointCloud & | projected_points, | ||
bool | copy_data_fields = true |
||
) | [pure virtual] |
Create a new point cloud with inliers projected onto the model. Pure virtual.
[in] | inliers | the data inliers that we want to project on the model |
[in] | model_coefficients | the coefficients of a model |
[out] | projected_points | the resultant projected points |
[in] | copy_data_fields | set to true (default) if we want the projected_points cloud to be an exact copy of the input dataset minus the point projections on the plane model |
Implemented in pcl::SampleConsensusModelCone< PointT, PointNT >, pcl::SampleConsensusModelPlane< PointT >, pcl::SampleConsensusModelCylinder< PointT, PointNT >, pcl::SampleConsensusModelRegistration< PointT >, pcl::SampleConsensusModelSphere< PointT >, pcl::SampleConsensusModelCircle2D< PointT >, pcl::SampleConsensusModelCircle3D< PointT >, pcl::SampleConsensusModelStick< PointT >, and pcl::SampleConsensusModelLine< PointT >.
int pcl::SampleConsensusModel< PointT >::rnd | ( | ) | [inline, protected] |
Boost-based random number generator.
Definition at line 544 of file sac_model.h.
virtual void pcl::SampleConsensusModel< PointT >::selectWithinDistance | ( | const Eigen::VectorXf & | model_coefficients, |
const double | threshold, | ||
std::vector< int > & | inliers | ||
) | [pure virtual] |
Select all the points which respect the given model coefficients as inliers. Pure virtual.
[in] | model_coefficients | the coefficients of a model that we need to compute distances to |
[in] | threshold | a maximum admissible distance threshold for determining the inliers from the outliers |
[out] | inliers | the resultant model inliers |
Implemented in pcl::SampleConsensusModelCone< PointT, PointNT >, pcl::SampleConsensusModelPlane< PointT >, pcl::SampleConsensusModelNormalParallelPlane< PointT, PointNT >, pcl::SampleConsensusModelCylinder< PointT, PointNT >, pcl::SampleConsensusModelRegistration< PointT >, pcl::SampleConsensusModelSphere< PointT >, pcl::SampleConsensusModelCircle2D< PointT >, pcl::SampleConsensusModelCircle3D< PointT >, pcl::SampleConsensusModelPerpendicularPlane< PointT >, pcl::SampleConsensusModelParallelPlane< PointT >, pcl::SampleConsensusModelNormalPlane< PointT, PointNT >, pcl::SampleConsensusModelParallelLine< PointT >, pcl::SampleConsensusModelStick< PointT >, pcl::SampleConsensusModelNormalSphere< PointT, PointNT >, pcl::SampleConsensusModelLine< PointT >, and pcl::SampleConsensusModelRegistration2D< PointT >.
void pcl::SampleConsensusModel< PointT >::setIndices | ( | const boost::shared_ptr< std::vector< int > > & | indices | ) | [inline] |
Provide a pointer to the vector of indices that represents the input data.
[in] | indices | a pointer to the vector of indices that represents the input data. |
Definition at line 327 of file sac_model.h.
void pcl::SampleConsensusModel< PointT >::setIndices | ( | const std::vector< int > & | indices | ) | [inline] |
Provide the vector of indices that represents the input data.
[out] | indices | the vector of indices that represents the input data. |
Definition at line 337 of file sac_model.h.
virtual void pcl::SampleConsensusModel< PointT >::setInputCloud | ( | const PointCloudConstPtr & | cloud | ) | [inline, virtual] |
Provide a pointer to the input dataset.
[in] | cloud | the const boost shared pointer to a PointCloud message |
Reimplemented in pcl::SampleConsensusModelRegistration< PointT >.
Definition at line 304 of file sac_model.h.
void pcl::SampleConsensusModel< PointT >::setRadiusLimits | ( | const double & | min_radius, |
const double & | max_radius | ||
) | [inline] |
Set the minimum and maximum allowable radius limits for the model (applicable to models that estimate a radius)
[in] | min_radius | the minimum radius model |
[in] | max_radius | the maximum radius model |
Definition at line 368 of file sac_model.h.
void pcl::SampleConsensusModel< PointT >::setSamplesMaxDist | ( | const double & | radius, |
SearchPtr | search | ||
) | [inline] |
Set the maximum distance allowed when drawing random samples.
[in] | radius | the maximum distance (L2 norm) |
Definition at line 391 of file sac_model.h.
friend class ProgressiveSampleConsensus< PointT > [friend] |
Definition at line 407 of file sac_model.h.
std::vector<double> pcl::SampleConsensusModel< PointT >::error_sqr_dists_ [protected] |
A vector holding the distances to the computed model. Used internally.
Definition at line 540 of file sac_model.h.
boost::shared_ptr<std::vector<int> > pcl::SampleConsensusModel< PointT >::indices_ [protected] |
A pointer to the vector of point indices to use.
Definition at line 511 of file sac_model.h.
PointCloudConstPtr pcl::SampleConsensusModel< PointT >::input_ [protected] |
A boost shared pointer to the point cloud data array.
Definition at line 508 of file sac_model.h.
const unsigned int pcl::SampleConsensusModel< PointT >::max_sample_checks_ = 1000 [static, protected] |
The maximum number of samples to try until we get a good one
Definition at line 514 of file sac_model.h.
double pcl::SampleConsensusModel< PointT >::radius_max_ [protected] |
Definition at line 519 of file sac_model.h.
double pcl::SampleConsensusModel< PointT >::radius_min_ [protected] |
The minimum and maximum radius limits for the model. Applicable to all models that estimate a radius.
Definition at line 519 of file sac_model.h.
boost::mt19937 pcl::SampleConsensusModel< PointT >::rng_alg_ [protected] |
Boost-based random number generator algorithm.
Definition at line 531 of file sac_model.h.
boost::shared_ptr<boost::uniform_int<> > pcl::SampleConsensusModel< PointT >::rng_dist_ [protected] |
Boost-based random number generator distribution.
Definition at line 534 of file sac_model.h.
boost::shared_ptr<boost::variate_generator< boost::mt19937&, boost::uniform_int<> > > pcl::SampleConsensusModel< PointT >::rng_gen_ [protected] |
Boost-based random number generator.
Definition at line 537 of file sac_model.h.
double pcl::SampleConsensusModel< PointT >::samples_radius_ [protected] |
The maximum distance of subsequent samples from the first (radius search)
Definition at line 522 of file sac_model.h.
SearchPtr pcl::SampleConsensusModel< PointT >::samples_radius_search_ [protected] |
The search object for picking subsequent samples using radius search.
Definition at line 525 of file sac_model.h.
std::vector<int> pcl::SampleConsensusModel< PointT >::shuffled_indices_ [protected] |
Data containing a shuffled version of the indices. This is used and modified when drawing samples.
Definition at line 528 of file sac_model.h.