Point Cloud Library (PCL)  1.5.1
 All Classes Namespaces Files Functions Variables Typedefs Enumerations Enumerator Friends Defines
registration.h
Go to the documentation of this file.
00001 /*
00002  * Software License Agreement (BSD License)
00003  *
00004  *  Point Cloud Library (PCL) - www.pointclouds.org
00005  *  Copyright (c) 2010-2011, Willow Garage, Inc.
00006  *
00007  *  All rights reserved.
00008  *
00009  *  Redistribution and use in source and binary forms, with or without
00010  *  modification, are permitted provided that the following conditions
00011  *  are met:
00012  *
00013  *   * Redistributions of source code must retain the above copyright
00014  *     notice, this list of conditions and the following disclaimer.
00015  *   * Redistributions in binary form must reproduce the above
00016  *     copyright notice, this list of conditions and the following
00017  *     disclaimer in the documentation and/or other materials provided
00018  *     with the distribution.
00019  *   * Neither the name of Willow Garage, Inc. nor the names of its
00020  *     contributors may be used to endorse or promote products derived
00021  *     from this software without specific prior written permission.
00022  *
00023  *  THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
00024  *  "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
00025  *  LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
00026  *  FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
00027  *  COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
00028  *  INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
00029  *  BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
00030  *  LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
00031  *  CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
00032  *  LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
00033  *  ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
00034  *  POSSIBILITY OF SUCH DAMAGE.
00035  *
00036  * $Id: registration.h 4702 2012-02-23 09:39:33Z gedikli $
00037  *
00038  */
00039 
00040 #ifndef PCL_REGISTRATION_H_
00041 #define PCL_REGISTRATION_H_
00042 
00043 #include <boost/function.hpp>
00044 #include <boost/bind.hpp>
00045 
00046 // PCL includes
00047 #include <pcl/pcl_base.h>
00048 #include <pcl/common/transforms.h>
00049 #include <pcl/pcl_macros.h>
00050 #include <pcl/kdtree/kdtree_flann.h>
00051 #include "pcl/registration/transformation_estimation.h"
00052 
00053 namespace pcl
00054 {
00060   template <typename PointSource, typename PointTarget>
00061   class Registration : public PCLBase<PointSource>
00062   {
00063     public:
00064       using PCLBase<PointSource>::initCompute;
00065       using PCLBase<PointSource>::deinitCompute;
00066       using PCLBase<PointSource>::input_;
00067       using PCLBase<PointSource>::indices_;
00068 
00069       typedef boost::shared_ptr< Registration<PointSource, PointTarget> > Ptr;
00070       typedef boost::shared_ptr< const Registration<PointSource, PointTarget> > ConstPtr;
00071 
00072       typedef typename pcl::KdTree<PointTarget> KdTree;
00073       typedef typename pcl::KdTree<PointTarget>::Ptr KdTreePtr;
00074      
00075       typedef pcl::PointCloud<PointSource> PointCloudSource;
00076       typedef typename PointCloudSource::Ptr PointCloudSourcePtr;
00077       typedef typename PointCloudSource::ConstPtr PointCloudSourceConstPtr;
00078 
00079       typedef pcl::PointCloud<PointTarget> PointCloudTarget;
00080       typedef typename PointCloudTarget::Ptr PointCloudTargetPtr;
00081       typedef typename PointCloudTarget::ConstPtr PointCloudTargetConstPtr;
00082 
00083       typedef typename KdTree::PointRepresentationConstPtr PointRepresentationConstPtr;
00084       
00085       typedef typename pcl::registration::TransformationEstimation<PointSource, PointTarget> TransformationEstimation;
00086       typedef typename TransformationEstimation::Ptr TransformationEstimationPtr;
00087       typedef typename TransformationEstimation::ConstPtr TransformationEstimationConstPtr;
00088 
00090       Registration () : nr_iterations_(0),
00091                         max_iterations_(10),
00092                         target_ (),
00093                         final_transformation_ (Eigen::Matrix4f::Identity ()),
00094                         transformation_ (Eigen::Matrix4f::Identity ()),
00095                         previous_transformation_ (Eigen::Matrix4f::Identity ()),
00096                         transformation_epsilon_ (0.0), 
00097                         euclidean_fitness_epsilon_ (-std::numeric_limits<double>::max ()),
00098                         corr_dist_threshold_ (std::sqrt (std::numeric_limits<double>::max ())),
00099                         inlier_threshold_ (0.05),
00100                         converged_ (false), min_number_correspondences_ (3), 
00101                         transformation_estimation_ (),
00102                         point_representation_ ()
00103       {
00104         tree_.reset (new pcl::KdTreeFLANN<PointTarget>);     // ANN tree for nearest neighbor search
00105         update_visualizer_ = NULL;
00106       }
00107 
00109       virtual ~Registration () {}
00110 
00114       void
00115       setTransformationEstimation (const TransformationEstimationPtr &te) { transformation_estimation_ = te; }
00116 
00120       virtual inline void 
00121       setInputTarget (const PointCloudTargetConstPtr &cloud);
00122 
00124       inline PointCloudTargetConstPtr const 
00125       getInputTarget () { return (target_ ); }
00126 
00128       inline Eigen::Matrix4f 
00129       getFinalTransformation () { return (final_transformation_); }
00130 
00132       inline Eigen::Matrix4f 
00133       getLastIncrementalTransformation () { return (transformation_); }
00134 
00138       inline void 
00139       setMaximumIterations (int nr_iterations) { max_iterations_ = nr_iterations; }
00140 
00142       inline int 
00143       getMaximumIterations () { return (max_iterations_); }
00144 
00148       inline void 
00149       setRANSACIterations (int ransac_iterations) { ransac_iterations_ = ransac_iterations; }
00150 
00152       inline double 
00153       getRANSACIterations () { return (ransac_iterations_); }
00154 
00162       inline void 
00163       setRANSACOutlierRejectionThreshold (double inlier_threshold) { inlier_threshold_ = inlier_threshold; }
00164 
00166       inline double 
00167       getRANSACOutlierRejectionThreshold () { return (inlier_threshold_); }
00168 
00174       inline void 
00175       setMaxCorrespondenceDistance (double distance_threshold) { corr_dist_threshold_ = distance_threshold; }
00176 
00180       inline double 
00181       getMaxCorrespondenceDistance () { return (corr_dist_threshold_); }
00182 
00189       inline void 
00190       setTransformationEpsilon (double epsilon) { transformation_epsilon_ = epsilon; }
00191 
00195       inline double 
00196       getTransformationEpsilon () { return (transformation_epsilon_); }
00197 
00206       inline void 
00207       setEuclideanFitnessEpsilon (double epsilon) { euclidean_fitness_epsilon_ = epsilon; }
00208 
00212       inline double 
00213       getEuclideanFitnessEpsilon () { return (euclidean_fitness_epsilon_); }
00214 
00218       inline void
00219       setPointRepresentation (const PointRepresentationConstPtr &point_representation)
00220       {
00221         point_representation_ = point_representation;
00222       }
00223 
00228       template<typename FunctionSignature> inline bool
00229       registerVisualizationCallback (boost::function<FunctionSignature> &visualizerCallback)
00230       {
00231         if (visualizerCallback != NULL)
00232         {
00233           update_visualizer_ = visualizerCallback;
00234           return (true);
00235         }
00236         else
00237           return (false);
00238       }
00239 
00244       inline double 
00245       getFitnessScore (double max_range = std::numeric_limits<double>::max ());
00246 
00252       inline double 
00253       getFitnessScore (const std::vector<float> &distances_a, const std::vector<float> &distances_b);
00254 
00256       inline bool 
00257       hasConverged () { return (converged_); }
00258 
00263       inline void 
00264       align (PointCloudSource &output);
00265 
00271       inline void 
00272       align (PointCloudSource &output, const Eigen::Matrix4f& guess);
00273 
00275       inline const std::string&
00276       getClassName () const { return (reg_name_); }
00277 
00278     protected:
00280       std::string reg_name_;
00281 
00283       KdTreePtr tree_;
00284 
00286       int nr_iterations_;
00287 
00289       int max_iterations_;
00290 
00292       int ransac_iterations_;
00293 
00295       PointCloudTargetConstPtr target_;
00296 
00298       Eigen::Matrix4f final_transformation_;
00299 
00301       Eigen::Matrix4f transformation_;
00302 
00304       Eigen::Matrix4f previous_transformation_;
00305 
00309       double transformation_epsilon_;
00310 
00315       double euclidean_fitness_epsilon_;
00316 
00320       double corr_dist_threshold_;
00321 
00326       double inlier_threshold_;
00327 
00329       bool converged_;
00330 
00334       int min_number_correspondences_;
00335 
00339       std::vector<float> correspondence_distances_;                                                              
00340 
00342       TransformationEstimationPtr transformation_estimation_;
00343 
00347       boost::function<void(const pcl::PointCloud<PointSource> &cloud_src,
00348                            const std::vector<int> &indices_src,
00349                            const pcl::PointCloud<PointTarget> &cloud_tgt,
00350                            const std::vector<int> &indices_tgt)> update_visualizer_;
00351 
00358       inline bool
00359       searchForNeighbors (const PointCloudSource &cloud, int index, 
00360                           std::vector<int> &indices, std::vector<float> &distances)
00361       {
00362         int k = tree_->nearestKSearch (cloud, index, 1, indices, distances);
00363         if (k == 0)
00364           return (false);
00365         return (true);
00366       }
00367 
00368     private:
00369  
00371       virtual void 
00372       computeTransformation (PointCloudSource &output, const Eigen::Matrix4f& guess) = 0;
00373 
00375       PointRepresentationConstPtr point_representation_;
00376     public:
00377       EIGEN_MAKE_ALIGNED_OPERATOR_NEW
00378    };
00379 }
00380 
00381 #include "pcl/registration/impl/registration.hpp"
00382 
00383 #endif  //#ifndef PCL_REGISTRATION_H_