CorrespondenceRejectorSampleConsensus implements a correspondence rejection using Random Sample Consensus to identify inliers (and reject outliers) More...
#include <correspondence_rejection_sample_consensus.h>
Public Types | |
typedef boost::shared_ptr < const CorrespondenceRejectorSampleConsensus > | ConstPtr |
typedef boost::shared_ptr < CorrespondenceRejectorSampleConsensus > | Ptr |
Public Member Functions | |
CorrespondenceRejectorSampleConsensus () | |
Empty constructor. Sets the inlier threshold to 5cm (0.05m), and the maximum number of iterations to 1000. | |
Eigen::Matrix4f | getBestTransformation () |
Get the best transformation after RANSAC rejection. | |
double | getInlierThreshold () |
Get the maximum distance between corresponding points. | |
PointCloudConstPtr const | getInputSource () |
Get a pointer to the input point cloud dataset target. | |
PointCloudConstPtr const | getInputTarget () |
Get a pointer to the input point cloud dataset target. | |
int | getMaximumIterations () |
Get the maximum number of iterations. | |
bool | getRefineModel () const |
Get the internal refine parameter value as set by the user using setRefineModel. | |
void | getRemainingCorrespondences (const pcl::Correspondences &original_correspondences, pcl::Correspondences &remaining_correspondences) |
Get a list of valid correspondences after rejection from the original set of correspondences. | |
PCL_DEPRECATED (virtual void setInputCloud(const PointCloudConstPtr &cloud),"[pcl::registration::CorrespondenceRejectorSampleConsensus::setInputCloud] setInputCloud is deprecated. Please use setInputSource instead.") | |
Provide a source point cloud dataset (must contain XYZ data!) | |
PCL_DEPRECATED (PointCloudConstPtr const getInputCloud(),"[pcl::registration::CorrespondenceRejectorSampleConsensus::getInputCloud] getInputCloud is deprecated. Please use getInputSource instead.") | |
Get a pointer to the input point cloud dataset target. | |
PCL_DEPRECATED (virtual void setTargetCloud(const PointCloudConstPtr &cloud),"[pcl::registration::CorrespondenceRejectorSampleConsensus::setTargetCloud] setTargetCloud is deprecated. Please use setInputTarget instead.") | |
Provide a target point cloud dataset (must contain XYZ data!) | |
PCL_DEPRECATED (void setMaxIterations(int max_iterations),"[pcl::registration::CorrespondenceRejectorSampleConsensus::setMaxIterations] setMaxIterations is deprecated. Please use setMaximumIterations instead.") | |
Set the maximum number of iterations. | |
PCL_DEPRECATED (int getMaxIterations(),"[pcl::registration::CorrespondenceRejectorSampleConsensus::getMaxIterations] getMaxIterations is deprecated. Please use getMaximumIterations instead.") | |
Get the maximum number of iterations. | |
void | setInlierThreshold (double threshold) |
Set the maximum distance between corresponding points. Correspondences with distances below the threshold are considered as inliers. | |
virtual void | setInputSource (const PointCloudConstPtr &cloud) |
Provide a source point cloud dataset (must contain XYZ data!) | |
virtual void | setInputTarget (const PointCloudConstPtr &cloud) |
Provide a target point cloud dataset (must contain XYZ data!) | |
void | setMaximumIterations (int max_iterations) |
Set the maximum number of iterations. | |
void | setRefineModel (const bool refine) |
Specify whether the model should be refined internally using the variance of the inliers. | |
virtual | ~CorrespondenceRejectorSampleConsensus () |
Empty destructor. | |
Protected Member Functions | |
void | applyRejection (pcl::Correspondences &correspondences) |
Apply the rejection algorithm. | |
Protected Attributes | |
Eigen::Matrix4f | best_transformation_ |
double | inlier_threshold_ |
PointCloudConstPtr | input_ |
PointCloudPtr | input_transformed_ |
int | max_iterations_ |
bool | refine_ |
PointCloudConstPtr | target_ |
Private Types | |
typedef pcl::PointCloud< PointT > | PointCloud |
typedef PointCloud::ConstPtr | PointCloudConstPtr |
typedef PointCloud::Ptr | PointCloudPtr |
CorrespondenceRejectorSampleConsensus implements a correspondence rejection using Random Sample Consensus to identify inliers (and reject outliers)
Definition at line 59 of file correspondence_rejection_sample_consensus.h.
typedef boost::shared_ptr<const CorrespondenceRejectorSampleConsensus> pcl::registration::CorrespondenceRejectorSampleConsensus< PointT >::ConstPtr |
Reimplemented from pcl::registration::CorrespondenceRejector.
Reimplemented in pcl::registration::CorrespondenceRejectorSampleConsensus2D< PointT >.
Definition at line 71 of file correspondence_rejection_sample_consensus.h.
typedef pcl::PointCloud<PointT> pcl::registration::CorrespondenceRejectorSampleConsensus< PointT >::PointCloud [private] |
Reimplemented in pcl::registration::CorrespondenceRejectorSampleConsensus2D< PointT >.
Definition at line 61 of file correspondence_rejection_sample_consensus.h.
typedef PointCloud::ConstPtr pcl::registration::CorrespondenceRejectorSampleConsensus< PointT >::PointCloudConstPtr [private] |
Reimplemented in pcl::registration::CorrespondenceRejectorSampleConsensus2D< PointT >.
Definition at line 63 of file correspondence_rejection_sample_consensus.h.
typedef PointCloud::Ptr pcl::registration::CorrespondenceRejectorSampleConsensus< PointT >::PointCloudPtr [private] |
Reimplemented in pcl::registration::CorrespondenceRejectorSampleConsensus2D< PointT >.
Definition at line 62 of file correspondence_rejection_sample_consensus.h.
typedef boost::shared_ptr<CorrespondenceRejectorSampleConsensus> pcl::registration::CorrespondenceRejectorSampleConsensus< PointT >::Ptr |
Reimplemented from pcl::registration::CorrespondenceRejector.
Reimplemented in pcl::registration::CorrespondenceRejectorSampleConsensus2D< PointT >.
Definition at line 70 of file correspondence_rejection_sample_consensus.h.
pcl::registration::CorrespondenceRejectorSampleConsensus< PointT >::CorrespondenceRejectorSampleConsensus | ( | ) | [inline] |
Empty constructor. Sets the inlier threshold to 5cm (0.05m), and the maximum number of iterations to 1000.
Definition at line 76 of file correspondence_rejection_sample_consensus.h.
virtual pcl::registration::CorrespondenceRejectorSampleConsensus< PointT >::~CorrespondenceRejectorSampleConsensus | ( | ) | [inline, virtual] |
Empty destructor.
Definition at line 89 of file correspondence_rejection_sample_consensus.h.
void pcl::registration::CorrespondenceRejectorSampleConsensus< PointT >::applyRejection | ( | pcl::Correspondences & | correspondences | ) | [inline, protected, virtual] |
Apply the rejection algorithm.
[out] | correspondences | the set of resultant correspondences. |
Implements pcl::registration::CorrespondenceRejector.
Reimplemented in pcl::registration::CorrespondenceRejectorSampleConsensus2D< PointT >.
Definition at line 198 of file correspondence_rejection_sample_consensus.h.
Eigen::Matrix4f pcl::registration::CorrespondenceRejectorSampleConsensus< PointT >::getBestTransformation | ( | ) | [inline] |
Get the best transformation after RANSAC rejection.
Definition at line 175 of file correspondence_rejection_sample_consensus.h.
double pcl::registration::CorrespondenceRejectorSampleConsensus< PointT >::getInlierThreshold | ( | ) | [inline] |
Get the maximum distance between corresponding points.
Definition at line 147 of file correspondence_rejection_sample_consensus.h.
PointCloudConstPtr const pcl::registration::CorrespondenceRejectorSampleConsensus< PointT >::getInputSource | ( | ) | [inline] |
Get a pointer to the input point cloud dataset target.
Definition at line 119 of file correspondence_rejection_sample_consensus.h.
PointCloudConstPtr const pcl::registration::CorrespondenceRejectorSampleConsensus< PointT >::getInputTarget | ( | ) | [inline] |
Get a pointer to the input point cloud dataset target.
Definition at line 134 of file correspondence_rejection_sample_consensus.h.
int pcl::registration::CorrespondenceRejectorSampleConsensus< PointT >::getMaximumIterations | ( | ) | [inline] |
Get the maximum number of iterations.
Definition at line 169 of file correspondence_rejection_sample_consensus.h.
bool pcl::registration::CorrespondenceRejectorSampleConsensus< PointT >::getRefineModel | ( | ) | const [inline] |
Get the internal refine parameter value as set by the user using setRefineModel.
Definition at line 188 of file correspondence_rejection_sample_consensus.h.
void pcl::registration::CorrespondenceRejectorSampleConsensus< PointT >::getRemainingCorrespondences | ( | const pcl::Correspondences & | original_correspondences, |
pcl::Correspondences & | remaining_correspondences | ||
) | [inline, virtual] |
Get a list of valid correspondences after rejection from the original set of correspondences.
[in] | original_correspondences | the set of initial correspondences given |
[out] | remaining_correspondences | the resultant filtered set of remaining correspondences |
Implements pcl::registration::CorrespondenceRejector.
Reimplemented in pcl::registration::CorrespondenceRejectorSampleConsensus2D< PointT >.
Definition at line 85 of file correspondence_rejection_sample_consensus.hpp.
pcl::registration::CorrespondenceRejectorSampleConsensus< PointT >::PCL_DEPRECATED | ( | virtual void | setInputCloudconst PointCloudConstPtr &cloud, |
" setInputCloud is deprecated. Please use setInputSource instead." | [pcl::registration::CorrespondenceRejectorSampleConsensus::setInputCloud] | ||
) |
Provide a source point cloud dataset (must contain XYZ data!)
[in] | cloud | a cloud containing XYZ data |
pcl::registration::CorrespondenceRejectorSampleConsensus< PointT >::PCL_DEPRECATED | ( | PointCloudConstPtr const | getInputCloud(), |
" getInputCloud is deprecated. Please use getInputSource instead." | [pcl::registration::CorrespondenceRejectorSampleConsensus::getInputCloud] | ||
) |
Get a pointer to the input point cloud dataset target.
pcl::registration::CorrespondenceRejectorSampleConsensus< PointT >::PCL_DEPRECATED | ( | virtual void | setTargetCloudconst PointCloudConstPtr &cloud, |
" setTargetCloud is deprecated. Please use setInputTarget instead." | [pcl::registration::CorrespondenceRejectorSampleConsensus::setTargetCloud] | ||
) |
Provide a target point cloud dataset (must contain XYZ data!)
[in] | cloud | a cloud containing XYZ data |
pcl::registration::CorrespondenceRejectorSampleConsensus< PointT >::PCL_DEPRECATED | ( | void | setMaxIterationsint max_iterations, |
" setMaxIterations is deprecated. Please use setMaximumIterations instead." | [pcl::registration::CorrespondenceRejectorSampleConsensus::setMaxIterations] | ||
) |
Set the maximum number of iterations.
[in] | max_iterations | Maximum number if iterations to run |
pcl::registration::CorrespondenceRejectorSampleConsensus< PointT >::PCL_DEPRECATED | ( | int | getMaxIterations(), |
" getMaxIterations is deprecated. Please use getMaximumIterations instead." | [pcl::registration::CorrespondenceRejectorSampleConsensus::getMaxIterations] | ||
) |
Get the maximum number of iterations.
void pcl::registration::CorrespondenceRejectorSampleConsensus< PointT >::setInlierThreshold | ( | double | threshold | ) | [inline] |
Set the maximum distance between corresponding points. Correspondences with distances below the threshold are considered as inliers.
[in] | threshold | Distance threshold in the same dimension as source and target data sets. |
Definition at line 141 of file correspondence_rejection_sample_consensus.h.
virtual void pcl::registration::CorrespondenceRejectorSampleConsensus< PointT >::setInputSource | ( | const PointCloudConstPtr & | cloud | ) | [inline, virtual] |
Provide a source point cloud dataset (must contain XYZ data!)
[in] | cloud | a cloud containing XYZ data |
Definition at line 112 of file correspondence_rejection_sample_consensus.h.
virtual void pcl::registration::CorrespondenceRejectorSampleConsensus< PointT >::setInputTarget | ( | const PointCloudConstPtr & | cloud | ) | [inline, virtual] |
Provide a target point cloud dataset (must contain XYZ data!)
[in] | cloud | a cloud containing XYZ data |
Definition at line 130 of file correspondence_rejection_sample_consensus.h.
void pcl::registration::CorrespondenceRejectorSampleConsensus< PointT >::setMaximumIterations | ( | int | max_iterations | ) | [inline] |
Set the maximum number of iterations.
[in] | max_iterations | Maximum number if iterations to run |
Definition at line 158 of file correspondence_rejection_sample_consensus.h.
void pcl::registration::CorrespondenceRejectorSampleConsensus< PointT >::setRefineModel | ( | const bool | refine | ) | [inline] |
Specify whether the model should be refined internally using the variance of the inliers.
[in] | refine | true if the model should be refined, false otherwise |
Definition at line 181 of file correspondence_rejection_sample_consensus.h.
Eigen::Matrix4f pcl::registration::CorrespondenceRejectorSampleConsensus< PointT >::best_transformation_ [protected] |
Definition at line 211 of file correspondence_rejection_sample_consensus.h.
double pcl::registration::CorrespondenceRejectorSampleConsensus< PointT >::inlier_threshold_ [protected] |
Definition at line 203 of file correspondence_rejection_sample_consensus.h.
PointCloudConstPtr pcl::registration::CorrespondenceRejectorSampleConsensus< PointT >::input_ [protected] |
Definition at line 207 of file correspondence_rejection_sample_consensus.h.
PointCloudPtr pcl::registration::CorrespondenceRejectorSampleConsensus< PointT >::input_transformed_ [protected] |
Definition at line 208 of file correspondence_rejection_sample_consensus.h.
int pcl::registration::CorrespondenceRejectorSampleConsensus< PointT >::max_iterations_ [protected] |
Definition at line 205 of file correspondence_rejection_sample_consensus.h.
bool pcl::registration::CorrespondenceRejectorSampleConsensus< PointT >::refine_ [protected] |
Definition at line 213 of file correspondence_rejection_sample_consensus.h.
PointCloudConstPtr pcl::registration::CorrespondenceRejectorSampleConsensus< PointT >::target_ [protected] |
Definition at line 209 of file correspondence_rejection_sample_consensus.h.