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 #ifndef _REGISTRATION_CORRESPONDENCES_CHECK_H_
00035 #define _REGISTRATION_CORRESPONDENCES_CHECK_H_
00036 
00037 #include <boost/function.hpp>
00038 #include <boost/bind.hpp>
00039 
00040 
00041 #include <pcl/pcl_base.h>
00042 
00043 #include "pcl/kdtree/kdtree.h"
00044 #include "pcl/kdtree/kdtree_flann.h"
00045 
00046 #include "pcl/registration/transforms.h"
00047 
00048 namespace pcl
00049 {
00053 
00056   template <typename PointSource, typename PointTarget>
00057   class RegistrationCorrespondencesCheck: public PCLBase<PointSource>
00058   {
00059     using PCLBase<PointSource>::initCompute;
00060     using PCLBase<PointSource>::deinitCompute;
00061 
00062     public:
00063       using PCLBase<PointSource>::input_;
00064       using PCLBase<PointSource>::indices_;
00065 
00066       typedef typename pcl::KdTree<PointTarget> KdTree;
00067       typedef typename pcl::KdTree<PointTarget>::Ptr KdTreePtr;
00068 
00069       typedef pcl::PointCloud<PointSource> PointCloudSource;
00070       typedef typename PointCloudSource::Ptr PointCloudSourcePtr;
00071       typedef typename PointCloudSource::ConstPtr PointCloudSourceConstPtr;
00072 
00073       typedef pcl::PointCloud<PointTarget> PointCloudTarget;
00074       typedef typename PointCloudTarget::Ptr PointCloudTargetPtr;
00075       typedef typename PointCloudTarget::ConstPtr PointCloudTargetConstPtr;
00076 
00078 
00079       RegistrationCorrespondencesCheck () : target_ (),
00080                         final_transformation_ (Eigen::Matrix4f::Identity ()),
00081                         transformation_ (Eigen::Matrix4f::Identity ()),
00082                         previous_transformation_ (Eigen::Matrix4f::Identity ()),
00083                         transformation_epsilon_ (0.0), corr_dist_threshold_ (std::numeric_limits<double>::max ()),
00084                         converged_ (false), min_number_correspondences_ (3), k_ (1)
00085       {
00086         tree_ = boost::make_shared<pcl::KdTreeFLANN<PointTarget> > ();     
00087       }
00088 
00090 
00091       virtual ~RegistrationCorrespondencesCheck () {};
00092 
00094 
00098       virtual inline void setInputTarget (const PointCloudTargetConstPtr &cloud);
00099 
00101 
00102       inline PointCloudTargetConstPtr const getInputTarget () { return (target_ ); }
00103 
00105 
00106       inline Eigen::Matrix4f getFinalTransformation () { return (final_transformation_); }
00107 
00109 
00110       inline Eigen::Matrix4f getLastIncrementalTransformation () { return (transformation_); }
00111 
00113 
00116       inline void setMaximumIterations (int nr_iterations) { max_iterations_ = nr_iterations; }
00117 
00119 
00120       inline int getMaximumIterations () { return (max_iterations_); }
00121 
00123 
00128       inline void setMaxCorrespondenceDistance (double distance_threshold) { corr_dist_threshold_ = distance_threshold; }
00129 
00131 
00134       inline double getMaxCorrespondenceDistance () { return (corr_dist_threshold_); }
00135 
00137 
00142       inline void setTransformationEpsilon (double epsilon) { transformation_epsilon_ = epsilon; }
00143 
00145 
00148       inline double getTransformationEpsilon () { return (transformation_epsilon_); }
00149 
00150 
00152 
00155       inline void
00156         setPointRepresentation (const typename KdTree::PointRepresentationConstPtr &point_representation)
00157       {
00158         tree_->setPointRepresentation (point_representation);
00159       }
00160 
00162 
00165       inline double getFitnessScore (double max_range = std::numeric_limits<double>::max ());
00166 
00168 
00171       inline void align (PointCloudSource &output);
00172 
00173     protected:
00175       std::string reg_name_;
00176 
00178       KdTreePtr tree_;
00179 
00181       int nr_iterations_;
00182 
00184       int max_iterations_;
00185 
00187       PointCloudTargetConstPtr target_;
00188 
00190       Eigen::Matrix4f final_transformation_;
00191 
00193       Eigen::Matrix4f transformation_;
00194 
00196       Eigen::Matrix4f previous_transformation_;
00197 
00199       double transformation_epsilon_;
00200 
00204       double corr_dist_threshold_;
00205 
00207       bool converged_;
00208 
00210       int min_number_correspondences_;
00211 
00213 
00221       inline bool
00222         searchForNeighbors (const PointCloudSource &cloud, int index, double radius, int max_nn, std::vector<int> &indices, std::vector<float> &distances)
00223       {
00224         return (tree_->radiusSearch (cloud, index, radius, indices, distances, max_nn));
00225       }
00226 
00228 
00229       inline const std::string& getClassName () const { return (reg_name_); }
00230 
00231     private:
00233 
00234       virtual void computeTransformation (PointCloudSource &output) = 0;
00235 
00237       int k_;
00238   };
00239 }
00240 
00241 #include "pointcloud_registration/icp/registration_correspondences_check.hpp"
00242 
00243 #endif  //#ifndef _REGISTRATION_CORRESPONDENCES_CHECK_H_