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
00041 #ifndef PCL_REGISTRATION_H_
00042 #define PCL_REGISTRATION_H_
00043
00044
00045 #include <pcl/pcl_base.h>
00046 #include <pcl/common/transforms.h>
00047 #include <pcl/pcl_macros.h>
00048 #include <pcl/search/kdtree.h>
00049 #include <pcl/kdtree/kdtree_flann.h>
00050 #include <pcl/registration/boost.h>
00051 #include <pcl/registration/transformation_estimation.h>
00052 #include <pcl/registration/correspondence_estimation.h>
00053 #include <pcl/registration/correspondence_rejection.h>
00054
00055 namespace pcl
00056 {
00061 template <typename PointSource, typename PointTarget, typename Scalar = float>
00062 class Registration : public PCLBase<PointSource>
00063 {
00064 public:
00065 typedef Eigen::Matrix<Scalar, 4, 4> Matrix4;
00066
00067
00068 using PCLBase<PointSource>::deinitCompute;
00069 using PCLBase<PointSource>::input_;
00070 using PCLBase<PointSource>::indices_;
00071
00072 typedef boost::shared_ptr< Registration<PointSource, PointTarget, Scalar> > Ptr;
00073 typedef boost::shared_ptr< const Registration<PointSource, PointTarget, Scalar> > ConstPtr;
00074
00075 typedef typename pcl::registration::CorrespondenceRejector::Ptr CorrespondenceRejectorPtr;
00076 typedef pcl::search::KdTree<PointTarget> KdTree;
00077 typedef typename pcl::search::KdTree<PointTarget>::Ptr KdTreePtr;
00078
00079 typedef pcl::search::KdTree<PointSource> KdTreeReciprocal;
00080 typedef typename KdTree::Ptr KdTreeReciprocalPtr;
00081
00082 typedef pcl::PointCloud<PointSource> PointCloudSource;
00083 typedef typename PointCloudSource::Ptr PointCloudSourcePtr;
00084 typedef typename PointCloudSource::ConstPtr PointCloudSourceConstPtr;
00085
00086 typedef pcl::PointCloud<PointTarget> PointCloudTarget;
00087 typedef typename PointCloudTarget::Ptr PointCloudTargetPtr;
00088 typedef typename PointCloudTarget::ConstPtr PointCloudTargetConstPtr;
00089
00090 typedef typename KdTree::PointRepresentationConstPtr PointRepresentationConstPtr;
00091
00092 typedef typename pcl::registration::TransformationEstimation<PointSource, PointTarget, Scalar> TransformationEstimation;
00093 typedef typename TransformationEstimation::Ptr TransformationEstimationPtr;
00094 typedef typename TransformationEstimation::ConstPtr TransformationEstimationConstPtr;
00095
00096 typedef typename pcl::registration::CorrespondenceEstimationBase<PointSource, PointTarget, Scalar> CorrespondenceEstimation;
00097 typedef typename CorrespondenceEstimation::Ptr CorrespondenceEstimationPtr;
00098 typedef typename CorrespondenceEstimation::ConstPtr CorrespondenceEstimationConstPtr;
00099
00101 Registration ()
00102 : reg_name_ ()
00103 , tree_ (new KdTree)
00104 , tree_reciprocal_ (new KdTreeReciprocal)
00105 , nr_iterations_ (0)
00106 , max_iterations_ (10)
00107 , ransac_iterations_ (0)
00108 , target_ ()
00109 , final_transformation_ (Matrix4::Identity ())
00110 , transformation_ (Matrix4::Identity ())
00111 , previous_transformation_ (Matrix4::Identity ())
00112 , transformation_epsilon_ (0.0)
00113 , euclidean_fitness_epsilon_ (-std::numeric_limits<double>::max ())
00114 , corr_dist_threshold_ (std::sqrt (std::numeric_limits<double>::max ()))
00115 , inlier_threshold_ (0.05)
00116 , converged_ (false)
00117 , min_number_correspondences_ (3)
00118 , correspondences_ (new Correspondences)
00119 , transformation_estimation_ ()
00120 , correspondence_estimation_ ()
00121 , correspondence_rejectors_ ()
00122 , target_cloud_updated_ (true)
00123 , source_cloud_updated_ (true)
00124 , force_no_recompute_ (false)
00125 , force_no_recompute_reciprocal_ (false)
00126 , update_visualizer_ (NULL)
00127 , point_representation_ ()
00128 {
00129 }
00130
00132 virtual ~Registration () {}
00133
00149 void
00150 setTransformationEstimation (const TransformationEstimationPtr &te) { transformation_estimation_ = te; }
00151
00173 void
00174 setCorrespondenceEstimation (const CorrespondenceEstimationPtr &ce) { correspondence_estimation_ = ce; }
00175
00181 PCL_DEPRECATED (void setInputCloud (const PointCloudSourceConstPtr &cloud), "[pcl::registration::Registration::setInputCloud] setInputCloud is deprecated. Please use setInputSource instead.");
00182
00184 PCL_DEPRECATED (PointCloudSourceConstPtr const getInputCloud (), "[pcl::registration::Registration::getInputCloud] getInputCloud is deprecated. Please use getInputSource instead.");
00185
00191 virtual void
00192 setInputSource (const PointCloudSourceConstPtr &cloud)
00193 {
00194 source_cloud_updated_ = true;
00195 PCLBase<PointSource>::setInputCloud (cloud);
00196 }
00197
00199 inline PointCloudSourceConstPtr const
00200 getInputSource () { return (input_ ); }
00201
00205 virtual inline void
00206 setInputTarget (const PointCloudTargetConstPtr &cloud);
00207
00209 inline PointCloudTargetConstPtr const
00210 getInputTarget () { return (target_ ); }
00211
00212
00220 inline void
00221 setSearchMethodTarget (const KdTreePtr &tree,
00222 bool force_no_recompute = false)
00223 {
00224 tree_ = tree;
00225 if (force_no_recompute)
00226 {
00227 force_no_recompute_ = true;
00228 }
00229
00230 target_cloud_updated_ = true;
00231 }
00232
00235 inline KdTreePtr
00236 getSearchMethodTarget () const
00237 {
00238 return (tree_);
00239 }
00240
00248 inline void
00249 setSearchMethodSource (const KdTreeReciprocalPtr &tree,
00250 bool force_no_recompute = false)
00251 {
00252 tree_reciprocal_ = tree;
00253 if ( force_no_recompute )
00254 {
00255 force_no_recompute_reciprocal_ = true;
00256 }
00257
00258 source_cloud_updated_ = true;
00259 }
00260
00263 inline KdTreeReciprocalPtr
00264 getSearchMethodSource () const
00265 {
00266 return (tree_reciprocal_);
00267 }
00268
00270 inline Matrix4
00271 getFinalTransformation () { return (final_transformation_); }
00272
00274 inline Matrix4
00275 getLastIncrementalTransformation () { return (transformation_); }
00276
00280 inline void
00281 setMaximumIterations (int nr_iterations) { max_iterations_ = nr_iterations; }
00282
00284 inline int
00285 getMaximumIterations () { return (max_iterations_); }
00286
00290 inline void
00291 setRANSACIterations (int ransac_iterations) { ransac_iterations_ = ransac_iterations; }
00292
00294 inline double
00295 getRANSACIterations () { return (ransac_iterations_); }
00296
00304 inline void
00305 setRANSACOutlierRejectionThreshold (double inlier_threshold) { inlier_threshold_ = inlier_threshold; }
00306
00308 inline double
00309 getRANSACOutlierRejectionThreshold () { return (inlier_threshold_); }
00310
00316 inline void
00317 setMaxCorrespondenceDistance (double distance_threshold) { corr_dist_threshold_ = distance_threshold; }
00318
00322 inline double
00323 getMaxCorrespondenceDistance () { return (corr_dist_threshold_); }
00324
00331 inline void
00332 setTransformationEpsilon (double epsilon) { transformation_epsilon_ = epsilon; }
00333
00337 inline double
00338 getTransformationEpsilon () { return (transformation_epsilon_); }
00339
00348 inline void
00349 setEuclideanFitnessEpsilon (double epsilon) { euclidean_fitness_epsilon_ = epsilon; }
00350
00354 inline double
00355 getEuclideanFitnessEpsilon () { return (euclidean_fitness_epsilon_); }
00356
00360 inline void
00361 setPointRepresentation (const PointRepresentationConstPtr &point_representation)
00362 {
00363 point_representation_ = point_representation;
00364 }
00365
00370 template<typename FunctionSignature> inline bool
00371 registerVisualizationCallback (boost::function<FunctionSignature> &visualizerCallback)
00372 {
00373 if (visualizerCallback != NULL)
00374 {
00375 update_visualizer_ = visualizerCallback;
00376 return (true);
00377 }
00378 else
00379 return (false);
00380 }
00381
00386 inline double
00387 getFitnessScore (double max_range = std::numeric_limits<double>::max ());
00388
00394 inline double
00395 getFitnessScore (const std::vector<float> &distances_a, const std::vector<float> &distances_b);
00396
00398 inline bool
00399 hasConverged () { return (converged_); }
00400
00405 inline void
00406 align (PointCloudSource &output);
00407
00413 inline void
00414 align (PointCloudSource &output, const Matrix4& guess);
00415
00417 inline const std::string&
00418 getClassName () const { return (reg_name_); }
00419
00421 bool
00422 initCompute ();
00423
00425 bool
00426 initComputeReciprocal ();
00427
00444 inline void
00445 addCorrespondenceRejector (const CorrespondenceRejectorPtr &rejector)
00446 {
00447 correspondence_rejectors_.push_back (rejector);
00448 }
00449
00451 inline std::vector<CorrespondenceRejectorPtr>
00452 getCorrespondenceRejectors ()
00453 {
00454 return (correspondence_rejectors_);
00455 }
00456
00460 inline bool
00461 removeCorrespondenceRejector (unsigned int i)
00462 {
00463 if (i >= correspondence_rejectors_.size ())
00464 return (false);
00465 correspondence_rejectors_.erase (correspondence_rejectors_.begin () + i);
00466 return (true);
00467 }
00468
00470 inline void
00471 clearCorrespondenceRejectors ()
00472 {
00473 correspondence_rejectors_.clear ();
00474 }
00475
00476 protected:
00478 std::string reg_name_;
00479
00481 KdTreePtr tree_;
00482
00484 KdTreeReciprocalPtr tree_reciprocal_;
00485
00487 int nr_iterations_;
00488
00492 int max_iterations_;
00493
00495 int ransac_iterations_;
00496
00498 PointCloudTargetConstPtr target_;
00499
00501 Matrix4 final_transformation_;
00502
00504 Matrix4 transformation_;
00505
00507 Matrix4 previous_transformation_;
00508
00512 double transformation_epsilon_;
00513
00518 double euclidean_fitness_epsilon_;
00519
00523 double corr_dist_threshold_;
00524
00529 double inlier_threshold_;
00530
00532 bool converged_;
00533
00537 int min_number_correspondences_;
00538
00540 CorrespondencesPtr correspondences_;
00541
00543 TransformationEstimationPtr transformation_estimation_;
00544
00546 CorrespondenceEstimationPtr correspondence_estimation_;
00547
00549 std::vector<CorrespondenceRejectorPtr> correspondence_rejectors_;
00550
00554 bool target_cloud_updated_;
00558 bool source_cloud_updated_;
00561 bool force_no_recompute_;
00562
00565 bool force_no_recompute_reciprocal_;
00566
00570 boost::function<void(const pcl::PointCloud<PointSource> &cloud_src,
00571 const std::vector<int> &indices_src,
00572 const pcl::PointCloud<PointTarget> &cloud_tgt,
00573 const std::vector<int> &indices_tgt)> update_visualizer_;
00574
00581 inline bool
00582 searchForNeighbors (const PointCloudSource &cloud, int index,
00583 std::vector<int> &indices, std::vector<float> &distances)
00584 {
00585 int k = tree_->nearestKSearch (cloud, index, 1, indices, distances);
00586 if (k == 0)
00587 return (false);
00588 return (true);
00589 }
00590
00592 virtual void
00593 computeTransformation (PointCloudSource &output, const Matrix4& guess) = 0;
00594
00595 private:
00597 PointRepresentationConstPtr point_representation_;
00598 public:
00599 EIGEN_MAKE_ALIGNED_OPERATOR_NEW
00600 };
00601 }
00602
00603 #include <pcl/registration/impl/registration.hpp>
00604
00605 #endif //#ifndef PCL_REGISTRATION_H_