Go to the documentation of this file.00001
00002
00003
00004
00005
00006
00007
00008
00009
00010
00011
00012
00013
00014
00015
00016
00017
00018
00019
00020
00021
00022
00023
00024
00025
00026
00027
00028
00029
00030
00031
00032
00033
00034
00035
00036
00037
00038
00039
00040 #ifndef PCL_REGISTRATION_CORRESPONDENCE_REJECTION_SAMPLE_CONSENSUS_H_
00041 #define PCL_REGISTRATION_CORRESPONDENCE_REJECTION_SAMPLE_CONSENSUS_H_
00042
00043 #include <pcl/registration/correspondence_rejection.h>
00044
00045 #include <pcl/sample_consensus/ransac.h>
00046 #include <pcl/sample_consensus/sac_model_registration.h>
00047 #include <pcl/common/transforms.h>
00048
00049 namespace pcl
00050 {
00051 namespace registration
00052 {
00058 template <typename PointT>
00059 class CorrespondenceRejectorSampleConsensus: public CorrespondenceRejector
00060 {
00061 typedef pcl::PointCloud<PointT> PointCloud;
00062 typedef typename PointCloud::Ptr PointCloudPtr;
00063 typedef typename PointCloud::ConstPtr PointCloudConstPtr;
00064
00065 public:
00066 using CorrespondenceRejector::input_correspondences_;
00067 using CorrespondenceRejector::rejection_name_;
00068 using CorrespondenceRejector::getClassName;
00069
00070 typedef boost::shared_ptr<CorrespondenceRejectorSampleConsensus> Ptr;
00071 typedef boost::shared_ptr<const CorrespondenceRejectorSampleConsensus> ConstPtr;
00072
00076 CorrespondenceRejectorSampleConsensus ()
00077 : inlier_threshold_ (0.05)
00078 , max_iterations_ (1000)
00079 , input_ ()
00080 , input_transformed_ ()
00081 , target_ ()
00082 , best_transformation_ ()
00083 , refine_ (false)
00084 {
00085 rejection_name_ = "CorrespondenceRejectorSampleConsensus";
00086 }
00087
00089 virtual ~CorrespondenceRejectorSampleConsensus () {}
00090
00095 inline void
00096 getRemainingCorrespondences (const pcl::Correspondences& original_correspondences,
00097 pcl::Correspondences& remaining_correspondences);
00098
00102 PCL_DEPRECATED (virtual void setInputCloud (const PointCloudConstPtr &cloud),
00103 "[pcl::registration::CorrespondenceRejectorSampleConsensus::setInputCloud] setInputCloud is deprecated. Please use setInputSource instead.");
00104
00106 PCL_DEPRECATED (PointCloudConstPtr const getInputCloud (), "[pcl::registration::CorrespondenceRejectorSampleConsensus::getInputCloud] getInputCloud is deprecated. Please use getInputSource instead.");
00107
00111 virtual inline void
00112 setInputSource (const PointCloudConstPtr &cloud)
00113 {
00114 input_ = cloud;
00115 }
00116
00118 inline PointCloudConstPtr const
00119 getInputSource () { return (input_); }
00120
00124 PCL_DEPRECATED (virtual void setTargetCloud (const PointCloudConstPtr &cloud), "[pcl::registration::CorrespondenceRejectorSampleConsensus::setTargetCloud] setTargetCloud is deprecated. Please use setInputTarget instead.");
00125
00129 virtual inline void
00130 setInputTarget (const PointCloudConstPtr &cloud) { target_ = cloud; }
00131
00133 inline PointCloudConstPtr const
00134 getInputTarget () { return (target_ ); }
00135
00140 inline void
00141 setInlierThreshold (double threshold) { inlier_threshold_ = threshold; };
00142
00146 inline double
00147 getInlierThreshold() { return inlier_threshold_; };
00148
00152 PCL_DEPRECATED (void setMaxIterations (int max_iterations), "[pcl::registration::CorrespondenceRejectorSampleConsensus::setMaxIterations] setMaxIterations is deprecated. Please use setMaximumIterations instead.");
00153
00157 inline void
00158 setMaximumIterations (int max_iterations) { max_iterations_ = std::max (max_iterations, 0); }
00159
00163 PCL_DEPRECATED (int getMaxIterations (), "[pcl::registration::CorrespondenceRejectorSampleConsensus::getMaxIterations] getMaxIterations is deprecated. Please use getMaximumIterations instead.");
00164
00168 inline int
00169 getMaximumIterations () { return (max_iterations_); }
00170
00174 inline Eigen::Matrix4f
00175 getBestTransformation () { return best_transformation_; };
00176
00180 inline void
00181 setRefineModel (const bool refine)
00182 {
00183 refine_ = refine;
00184 }
00185
00187 inline bool
00188 getRefineModel () const
00189 {
00190 return (refine_);
00191 }
00192 protected:
00193
00197 inline void
00198 applyRejection (pcl::Correspondences &correspondences)
00199 {
00200 getRemainingCorrespondences (*input_correspondences_, correspondences);
00201 }
00202
00203 double inlier_threshold_;
00204
00205 int max_iterations_;
00206
00207 PointCloudConstPtr input_;
00208 PointCloudPtr input_transformed_;
00209 PointCloudConstPtr target_;
00210
00211 Eigen::Matrix4f best_transformation_;
00212
00213 bool refine_;
00214 public:
00215 EIGEN_MAKE_ALIGNED_OPERATOR_NEW
00216 };
00217 }
00218 }
00219
00220 #include <pcl/registration/impl/correspondence_rejection_sample_consensus.hpp>
00221
00222 #endif // PCL_REGISTRATION_CORRESPONDENCE_REJECTION_SAMPLE_CONSENSUS_H_