gicp.h
Go to the documentation of this file.
00001 /*
00002  * Software License Agreement (BSD License)
00003  *
00004  *  Copyright (c) 2010, Willow Garage, Inc.
00005  *  All rights reserved.
00006  *
00007  *  Redistribution and use in source and binary forms, with or without
00008  *  modification, are permitted provided that the following conditions
00009  *  are met:
00010  *
00011  *   * Redistributions of source code must retain the above copyright
00012  *     notice, this list of conditions and the following disclaimer.
00013  *   * Redistributions in binary form must reproduce the above
00014  *     copyright notice, this list of conditions and the following
00015  *     disclaimer in the documentation and/or other materials provided
00016  *     with the distribution.
00017  *   * Neither the name of Willow Garage, Inc. nor the names of its
00018  *     contributors may be used to endorse or promote products derived
00019  *     from this software without specific prior written permission.
00020  *
00021  *  THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
00022  *  "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
00023  *  LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
00024  *  FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
00025  *  COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
00026  *  INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
00027  *  BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
00028  *  LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
00029  *  CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
00030  *  LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
00031  *  ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
00032  *  POSSIBILITY OF SUCH DAMAGE.
00033  *
00034  * $Id: gicp.h 5026 2012-03-12 02:51:44Z rusu $
00035  *
00036  */
00037 
00038 #ifndef PCL_GICP_H_
00039 #define PCL_GICP_H_
00040 
00041 #include <pcl/registration/icp.h>
00042 #include <pcl/registration/bfgs.h>
00043 
00044 namespace pcl
00045 {
00056   template <typename PointSource, typename PointTarget>
00057   class GeneralizedIterativeClosestPoint : public IterativeClosestPoint<PointSource, PointTarget>
00058   {
00059     using IterativeClosestPoint<PointSource, PointTarget>::reg_name_;
00060     using IterativeClosestPoint<PointSource, PointTarget>::getClassName;
00061     using IterativeClosestPoint<PointSource, PointTarget>::indices_;
00062     using IterativeClosestPoint<PointSource, PointTarget>::target_;
00063     using IterativeClosestPoint<PointSource, PointTarget>::input_;
00064     using IterativeClosestPoint<PointSource, PointTarget>::tree_;
00065     using IterativeClosestPoint<PointSource, PointTarget>::nr_iterations_;
00066     using IterativeClosestPoint<PointSource, PointTarget>::max_iterations_;
00067     using IterativeClosestPoint<PointSource, PointTarget>::previous_transformation_;
00068     using IterativeClosestPoint<PointSource, PointTarget>::final_transformation_;
00069     using IterativeClosestPoint<PointSource, PointTarget>::transformation_;
00070     using IterativeClosestPoint<PointSource, PointTarget>::transformation_epsilon_;
00071     using IterativeClosestPoint<PointSource, PointTarget>::converged_;
00072     using IterativeClosestPoint<PointSource, PointTarget>::corr_dist_threshold_;
00073     using IterativeClosestPoint<PointSource, PointTarget>::inlier_threshold_;
00074     using IterativeClosestPoint<PointSource, PointTarget>::min_number_correspondences_;
00075     using IterativeClosestPoint<PointSource, PointTarget>::update_visualizer_;
00076 
00077     typedef pcl::PointCloud<PointSource> PointCloudSource;
00078     typedef typename PointCloudSource::Ptr PointCloudSourcePtr;
00079     typedef typename PointCloudSource::ConstPtr PointCloudSourceConstPtr;
00080 
00081     typedef pcl::PointCloud<PointTarget> PointCloudTarget;
00082     typedef typename PointCloudTarget::Ptr PointCloudTargetPtr;
00083     typedef typename PointCloudTarget::ConstPtr PointCloudTargetConstPtr;
00084 
00085     typedef PointIndices::Ptr PointIndicesPtr;
00086     typedef PointIndices::ConstPtr PointIndicesConstPtr;
00087 
00088     typedef typename pcl::KdTree<PointSource> InputKdTree;
00089     typedef typename pcl::KdTree<PointSource>::Ptr InputKdTreePtr;
00090     
00091     typedef Eigen::Matrix<double, 6, 1> Vector6d;
00092 
00093     public:
00095       GeneralizedIterativeClosestPoint () 
00096         : k_correspondences_(20)
00097         , gicp_epsilon_(0.001)
00098         , rotation_epsilon_(2e-3)
00099         , input_covariances_(0)
00100         , target_covariances_(0)
00101         , mahalanobis_(0)
00102         , max_inner_iterations_(20)
00103       {
00104         min_number_correspondences_ = 4;
00105         reg_name_ = "GeneralizedIterativeClosestPoint";
00106         max_iterations_ = 200;
00107         transformation_epsilon_ = 5e-4;
00108         corr_dist_threshold_ = 5.;
00109         rigid_transformation_estimation_ = 
00110           boost::bind (&GeneralizedIterativeClosestPoint<PointSource, PointTarget>::estimateRigidTransformationBFGS, 
00111                        this, _1, _2, _3, _4, _5); 
00112         input_tree_.reset (new pcl::KdTreeFLANN<PointSource>);
00113       }
00114 
00118       inline void
00119       setInputCloud (const PointCloudSourceConstPtr &cloud)
00120       {
00121         if (cloud->points.empty ())
00122         {
00123           PCL_ERROR ("[pcl::%s::setInputInput] Invalid or empty point cloud dataset given!\n", getClassName ().c_str ());
00124           return;
00125         }
00126         PointCloudSource input = *cloud;
00127         // Set all the point.data[3] values to 1 to aid the rigid transformation
00128         for (size_t i = 0; i < input.size (); ++i)
00129           input[i].data[3] = 1.0;
00130         
00131         input_ = input.makeShared ();
00132         input_tree_->setInputCloud (input_);
00133         input_covariances_.reserve (input_->size ());
00134       }
00135 
00139       inline void 
00140       setInputTarget (const PointCloudTargetConstPtr &target)
00141       {
00142         pcl::Registration<PointSource, PointTarget>::setInputTarget(target);
00143         target_covariances_.reserve (target_->size ());
00144       }
00145 
00154       void
00155       estimateRigidTransformationBFGS (const PointCloudSource &cloud_src,
00156                                        const std::vector<int> &indices_src,
00157                                        const PointCloudTarget &cloud_tgt,
00158                                        const std::vector<int> &indices_tgt,
00159                                        Eigen::Matrix4f &transformation_matrix);
00160       
00162       inline const Eigen::Matrix3d& mahalanobis(size_t index) const
00163       {
00164         assert(index < mahalanobis_.size());
00165         return mahalanobis_[index];
00166       }
00167 
00175       void
00176       computeRDerivative(const Vector6d &x, const Eigen::Matrix3d &R, Vector6d &g) const;
00177 
00183       inline void 
00184       setRotationEpsilon (double epsilon) { rotation_epsilon_ = epsilon; }
00185 
00189       inline double 
00190       getRotationEpsilon () { return (rotation_epsilon_); }
00191 
00198       void
00199       setCorrespondenceRandomness (int k) { k_correspondences_ = k; }
00200 
00204       int
00205       getCorrespondenceRandomness () { return (k_correspondences_); }
00206 
00210       void
00211       setMaximumOptimizerIterations (int max) { max_inner_iterations_ = max; }
00212 
00214       int
00215       getMaximumOptimizerIterations () { return (max_inner_iterations_); }
00216 
00217     private:
00218 
00222       int k_correspondences_;
00223 
00228       double gicp_epsilon_;
00229 
00234       double rotation_epsilon_;
00235 
00237       Eigen::Matrix4f base_transformation_;
00238 
00240       const PointCloudSource *tmp_src_;
00241 
00243       const PointCloudTarget  *tmp_tgt_;
00244 
00246       const std::vector<int> *tmp_idx_src_;
00247 
00249       const std::vector<int> *tmp_idx_tgt_;
00250 
00252       InputKdTreePtr input_tree_;
00253       
00255       std::vector<Eigen::Matrix3d> input_covariances_;
00256 
00258       std::vector<Eigen::Matrix3d> target_covariances_;
00259 
00261       std::vector<Eigen::Matrix3d> mahalanobis_;
00262       
00264       int max_inner_iterations_;
00265 
00272       template<typename PointT>
00273       void computeCovariances(typename pcl::PointCloud<PointT>::ConstPtr cloud, 
00274                               const typename pcl::KdTree<PointT>::Ptr tree,
00275                               std::vector<Eigen::Matrix3d>& cloud_covariances);
00276 
00281       inline double 
00282       matricesInnerProd(const Eigen::MatrixXd& mat1, const Eigen::MatrixXd& mat2) const
00283       {
00284         double r = 0.;
00285         size_t n = mat1.rows();
00286         // tr(mat1^t.mat2)
00287         for(size_t i = 0; i < n; i++)
00288           for(size_t j = 0; j < n; j++)
00289             r += mat1 (j, i) * mat2 (i,j);
00290         return r;
00291       }
00292 
00297       void 
00298       computeTransformation (PointCloudSource &output, const Eigen::Matrix4f &guess);
00299 
00305       inline bool 
00306       searchForNeighbors (const PointSource &query, std::vector<int>& index, std::vector<float>& distance)
00307       {
00308         int k = tree_->nearestKSearch (query, 1, index, distance);
00309         if (k == 0)
00310           return (false);
00311         return (true);
00312       }
00313 
00315       void applyState(Eigen::Matrix4f &t, const Vector6d& x) const;
00316       
00318       struct OptimizationFunctorWithIndices : public BFGSDummyFunctor<double,6>
00319       {
00320         OptimizationFunctorWithIndices (const GeneralizedIterativeClosestPoint* gicp)
00321           : BFGSDummyFunctor<double,6> (), gicp_(gicp) {}
00322         double operator() (const Vector6d& x);
00323         void  df(const Vector6d &x, Vector6d &df);
00324         void fdf(const Vector6d &x, double &f, Vector6d &df);
00325 
00326         const GeneralizedIterativeClosestPoint *gicp_;
00327       };
00328       
00329     protected:
00330       boost::function<void(const pcl::PointCloud<PointSource> &cloud_src,
00331                            const std::vector<int> &src_indices,
00332                            const pcl::PointCloud<PointTarget> &cloud_tgt,
00333                            const std::vector<int> &tgt_indices,
00334                            Eigen::Matrix4f &transformation_matrix)> rigid_transformation_estimation_;
00335   };
00336 }
00337 
00338 #include <pcl/registration/impl/gicp.hpp>
00339 
00340 #endif  //#ifndef PCL_GICP_H_


pcl
Author(s): Open Perception
autogenerated on Mon Oct 6 2014 03:15:15