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 #ifndef PCL_REGISTRATION_H_
00039 #define PCL_REGISTRATION_H_
00040
00041 #include <boost/function.hpp>
00042 #include <boost/bind.hpp>
00043
00044
00045 #include <pcl/pcl_base.h>
00046
00047 #include "pcl/kdtree/kdtree.h"
00048 #include "pcl/kdtree/kdtree_flann.h"
00049
00050 #include "pcl/registration/transforms.h"
00051
00052 #include <Eigen/SVD>
00053
00054 #include "pcl/win32_macros.h"
00055
00056 namespace pcl
00057 {
00063 template <typename PointSource, typename PointTarget> inline void
00064 estimateRigidTransformationSVD (const pcl::PointCloud<PointSource> &cloud_src,
00065 const pcl::PointCloud<PointTarget> &cloud_tgt,
00066 Eigen::Matrix4f &transformation_matrix);
00067
00074 template <typename PointSource, typename PointTarget> inline void
00075 estimateRigidTransformationSVD (const pcl::PointCloud<PointSource> &cloud_src, const std::vector<int> &indices_src,
00076 const pcl::PointCloud<PointTarget> &cloud_tgt,
00077 Eigen::Matrix4f &transformation_matrix);
00078
00086 template <typename PointSource, typename PointTarget> inline void
00087 estimateRigidTransformationSVD (const pcl::PointCloud<PointSource> &cloud_src, const std::vector<int> &indices_src,
00088 const pcl::PointCloud<PointTarget> &cloud_tgt, const std::vector<int> &indices_tgt,
00089 Eigen::Matrix4f &transformation_matrix);
00090
00091
00096 template <typename PointSource, typename PointTarget>
00097 class Registration : public PCLBase<PointSource>
00098 {
00099 class FeatureContainerInterface;
00100
00101 public:
00102 using PCLBase<PointSource>::initCompute;
00103 using PCLBase<PointSource>::deinitCompute;
00104 using PCLBase<PointSource>::input_;
00105 using PCLBase<PointSource>::indices_;
00106
00107 typedef typename pcl::KdTree<PointTarget> KdTree;
00108 typedef typename pcl::KdTree<PointTarget>::Ptr KdTreePtr;
00109
00110 typedef pcl::PointCloud<PointSource> PointCloudSource;
00111 typedef typename PointCloudSource::Ptr PointCloudSourcePtr;
00112 typedef typename PointCloudSource::ConstPtr PointCloudSourceConstPtr;
00113
00114 typedef pcl::PointCloud<PointTarget> PointCloudTarget;
00115 typedef typename PointCloudTarget::Ptr PointCloudTargetPtr;
00116 typedef typename PointCloudTarget::ConstPtr PointCloudTargetConstPtr;
00117
00118 typedef typename KdTree::PointRepresentationConstPtr PointRepresentationConstPtr;
00119
00120 typedef std::map<std::string, boost::shared_ptr<FeatureContainerInterface> > FeaturesMap;
00121
00123 Registration () : target_ (),
00124 final_transformation_ (Eigen::Matrix4f::Identity ()),
00125 transformation_ (Eigen::Matrix4f::Identity ()),
00126 previous_transformation_ (Eigen::Matrix4f::Identity ()),
00127 transformation_epsilon_ (0.0), corr_dist_threshold_ (std::numeric_limits<double>::max ()),
00128 inlier_threshold_ (0.05),
00129 converged_ (false), min_number_correspondences_ (3), point_representation_ ()
00130 {
00131 tree_ = boost::make_shared<pcl::KdTreeFLANN<PointTarget> > ();
00132 }
00133
00137 virtual inline void
00138 setInputTarget (const PointCloudTargetConstPtr &cloud);
00139
00141 inline PointCloudTargetConstPtr const
00142 getInputTarget () { return (target_ ); }
00143
00148 template <typename FeatureType> inline void
00149 setSourceFeature (const typename pcl::PointCloud<FeatureType>::ConstPtr &source_feature, std::string key);
00150
00154 template <typename FeatureType> inline typename pcl::PointCloud<FeatureType>::ConstPtr
00155 getSourceFeature (std::string key);
00156
00161 template <typename FeatureType> inline void
00162 setTargetFeature (const typename pcl::PointCloud<FeatureType>::ConstPtr &target_feature, std::string key);
00163
00167 template <typename FeatureType> inline typename pcl::PointCloud<FeatureType>::ConstPtr
00168 getTargetFeature (std::string key);
00169
00176 template <typename FeatureType> inline void
00177 setRadiusSearch (const typename pcl::KdTree<FeatureType>::Ptr &tree, float r, std::string key);
00178
00185 template <typename FeatureType> inline void
00186 setKSearch (const typename pcl::KdTree<FeatureType>::Ptr &tree, int k, std::string key);
00187
00189 inline Eigen::Matrix4f
00190 getFinalTransformation () { return (final_transformation_); }
00191
00193 inline Eigen::Matrix4f
00194 getLastIncrementalTransformation () { return (transformation_); }
00195
00199 inline void
00200 setMaximumIterations (int nr_iterations) { max_iterations_ = nr_iterations; }
00201
00203 inline int
00204 getMaximumIterations () { return (max_iterations_); }
00205
00213 inline void
00214 setRANSACOutlierRejectionThreshold (double inlier_threshold) { inlier_threshold_ = inlier_threshold; }
00215
00217 inline double
00218 getRANSACOutlierRejectionThreshold () { return (inlier_threshold_); }
00219
00225 inline void
00226 setMaxCorrespondenceDistance (double distance_threshold) { corr_dist_threshold_ = distance_threshold; }
00227
00231 inline double
00232 getMaxCorrespondenceDistance () { return (corr_dist_threshold_); }
00233
00239 inline void
00240 setTransformationEpsilon (double epsilon) { transformation_epsilon_ = epsilon; }
00241
00245 inline double
00246 getTransformationEpsilon () { return (transformation_epsilon_); }
00247
00251 inline void
00252 setPointRepresentation (const PointRepresentationConstPtr &point_representation)
00253 {
00254 point_representation_ = point_representation;
00255 }
00256
00261 inline double
00262 getFitnessScore (double max_range = std::numeric_limits<double>::max ());
00263
00265 inline bool
00266 hasConverged () { return (converged_); }
00267
00272 inline void
00273 align (PointCloudSource &output);
00274
00275 protected:
00277 std::string reg_name_;
00278
00280 KdTreePtr tree_;
00281
00283 int nr_iterations_;
00284
00286 int max_iterations_;
00287
00289 PointCloudTargetConstPtr target_;
00290
00292 Eigen::Matrix4f final_transformation_;
00293
00295 Eigen::Matrix4f transformation_;
00296
00298 Eigen::Matrix4f previous_transformation_;
00299
00303 double transformation_epsilon_;
00304
00308 double corr_dist_threshold_;
00309
00314 double inlier_threshold_;
00315
00317 bool converged_;
00318
00322 int min_number_correspondences_;
00323
00330 inline bool
00331 searchForNeighbors (const PointCloudSource &cloud, int index,
00332 std::vector<int> &indices, std::vector<float> &distances)
00333 {
00334 int k = tree_->nearestKSearch (cloud, index, 1, indices, distances);
00335 if (k == 0)
00336 return (false);
00337 return (true);
00338 }
00339
00343 inline bool
00344 hasValidFeatures ();
00345
00351 inline void
00352 findFeatureCorrespondences (int index, std::vector<int> &correspondence_indices);
00353
00355 inline const std::string&
00356 getClassName () const { return (reg_name_); }
00357
00358 private:
00359
00361 virtual void
00362 computeTransformation (PointCloudSource &output) = 0;
00363
00364
00365
00366
00368 PointRepresentationConstPtr point_representation_;
00369
00371 FeaturesMap features_map_;
00372
00373
00379 template <typename FeatureType>
00380 class FeatureContainer : public pcl::Registration<PointSource, PointTarget>::FeatureContainerInterface
00381 {
00382 public:
00383 typedef typename pcl::PointCloud<FeatureType>::ConstPtr FeatureCloudConstPtr;
00384 typedef typename pcl::KdTree<FeatureType> KdTree;
00385 typedef typename pcl::KdTree<FeatureType>::Ptr KdTreePtr;
00386 typedef boost::function<int (const pcl::PointCloud<FeatureType> &, int, std::vector<int> &,
00387 std::vector<float> &)> SearchMethod;
00388
00389 FeatureContainer () : k_(0), radius_(0) {}
00390
00391 void setSourceFeature (const FeatureCloudConstPtr &source_features)
00392 {
00393 source_features_ = source_features;
00394 }
00395
00396 FeatureCloudConstPtr getSourceFeature ()
00397 {
00398 return (source_features_);
00399 }
00400
00401 void setTargetFeature (const FeatureCloudConstPtr &target_features)
00402 {
00403 target_features_ = target_features;
00404 if (tree_)
00405 {
00406 tree_->setInputCloud (target_features_);
00407 }
00408 }
00409
00410 FeatureCloudConstPtr getTargetFeature ()
00411 {
00412 return (target_features_);
00413 }
00414
00415 void setRadiusSearch (KdTreePtr tree, float r)
00416 {
00417 tree_ = tree;
00418 radius_ = r;
00419 k_ = 0;
00420 if (target_features_)
00421 {
00422 tree_->setInputCloud (target_features_);
00423 }
00424 }
00425
00426 void setKSearch (KdTreePtr tree, int k)
00427 {
00428 tree_ = tree;
00429 k_ = k;
00430 radius_ = 0.0;
00431 if (target_features_)
00432 {
00433 tree_->setInputCloud (target_features_);
00434 }
00435 }
00436
00437 virtual bool isValid ()
00438 {
00439 if (!source_features_ || !target_features_ || !tree_)
00440 {
00441 return (false);
00442 }
00443 else
00444 {
00445 return (source_features_->points.size () > 0 &&
00446 target_features_->points.size () > 0 &&
00447 (k_ > 0 || radius_ > 0.0));
00448 }
00449 }
00450
00451 virtual void findFeatureCorrespondences (int index, std::vector<int> &correspondence_indices,
00452 std::vector<float> &distances)
00453 {
00454 if (k_ > 0)
00455 {
00456 correspondence_indices.resize (k_);
00457 distances.resize (k_);
00458 tree_->nearestKSearch (*source_features_, index, k_, correspondence_indices, distances);
00459 }
00460 else
00461 {
00462 tree_->radiusSearch (*source_features_, index, radius_, correspondence_indices, distances);
00463 }
00464 }
00465
00466 private:
00467 FeatureCloudConstPtr source_features_, target_features_;
00468 KdTreePtr tree_;
00469 SearchMethod search_method_;
00470 int k_;
00471 double radius_;
00472 };
00473
00474 class FeatureContainerInterface
00475 {
00476 public:
00477 virtual bool isValid () = 0;
00478 virtual void findFeatureCorrespondences (int index, std::vector<int> &correspondence_indices,
00479 std::vector<float> &distances) = 0;
00480 };
00481
00482 };
00483 }
00484
00485 #include "pcl/registration/registration.hpp"
00486
00487 #endif //#ifndef PCL_REGISTRATION_H_