ia_ransac.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-2012, 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  *
00037  */
00038 #ifndef IA_RANSAC_H_
00039 #define IA_RANSAC_H_
00040 
00041 #include <pcl/registration/registration.h>
00042 #include <pcl/registration/transformation_estimation_svd.h>
00043 
00044 namespace pcl
00045 {
00051   template <typename PointSource, typename PointTarget, typename FeatureT>
00052   class SampleConsensusInitialAlignment : public Registration<PointSource, PointTarget>
00053   {
00054     public:
00055       using Registration<PointSource, PointTarget>::reg_name_;
00056       using Registration<PointSource, PointTarget>::input_;
00057       using Registration<PointSource, PointTarget>::indices_;
00058       using Registration<PointSource, PointTarget>::target_;
00059       using Registration<PointSource, PointTarget>::final_transformation_;
00060       using Registration<PointSource, PointTarget>::transformation_;
00061       using Registration<PointSource, PointTarget>::corr_dist_threshold_;
00062       using Registration<PointSource, PointTarget>::min_number_correspondences_;
00063       using Registration<PointSource, PointTarget>::max_iterations_;
00064       using Registration<PointSource, PointTarget>::tree_;
00065       using Registration<PointSource, PointTarget>::transformation_estimation_;
00066       using Registration<PointSource, PointTarget>::getClassName;
00067 
00068       typedef typename Registration<PointSource, PointTarget>::PointCloudSource PointCloudSource;
00069       typedef typename PointCloudSource::Ptr PointCloudSourcePtr;
00070       typedef typename PointCloudSource::ConstPtr PointCloudSourceConstPtr;
00071 
00072       typedef typename Registration<PointSource, PointTarget>::PointCloudTarget PointCloudTarget;
00073 
00074       typedef PointIndices::Ptr PointIndicesPtr;
00075       typedef PointIndices::ConstPtr PointIndicesConstPtr;
00076 
00077       typedef pcl::PointCloud<FeatureT> FeatureCloud;
00078       typedef typename FeatureCloud::Ptr FeatureCloudPtr;
00079       typedef typename FeatureCloud::ConstPtr FeatureCloudConstPtr;
00080 
00081 
00082       class ErrorFunctor
00083       {
00084         public:
00085           virtual ~ErrorFunctor () {}
00086           virtual float operator () (float d) const = 0;
00087       };
00088 
00089       class HuberPenalty : public ErrorFunctor
00090       {
00091         private:
00092           HuberPenalty () {}
00093         public:
00094           HuberPenalty (float threshold)  : threshold_ (threshold) {}
00095           virtual float operator () (float e) const
00096           { 
00097             if (e <= threshold_)
00098               return (0.5 * e*e); 
00099             else
00100               return (0.5 * threshold_ * (2.0 * fabs (e) - threshold_));
00101           }
00102         protected:
00103           float threshold_;
00104       };
00105 
00106       class TruncatedError : public ErrorFunctor
00107       {
00108         private:
00109           TruncatedError () {}
00110         public:
00111           virtual ~TruncatedError () {}
00112 
00113           TruncatedError (float threshold) : threshold_ (threshold) {}
00114           virtual float operator () (float e) const
00115           { 
00116             if (e <= threshold_)
00117               return (e / threshold_);
00118             else
00119               return (1.0);
00120           }
00121         protected:
00122           float threshold_;
00123       };
00124 
00125       typedef typename KdTreeFLANN<FeatureT>::Ptr FeatureKdTreePtr; 
00127       SampleConsensusInitialAlignment () : 
00128         input_features_ (), target_features_ (), 
00129         nr_samples_(3), min_sample_distance_ (0.0f), k_correspondences_ (10), 
00130         feature_tree_ (new pcl::KdTreeFLANN<FeatureT>),
00131         error_functor_ ()
00132       {
00133         reg_name_ = "SampleConsensusInitialAlignment";
00134         max_iterations_ = 1000;
00135         transformation_estimation_.reset (new pcl::registration::TransformationEstimationSVD<PointSource, PointTarget>);
00136       };
00137 
00141       void 
00142       setSourceFeatures (const FeatureCloudConstPtr &features);
00143 
00145       inline FeatureCloudConstPtr const 
00146       getSourceFeatures () { return (input_features_); }
00147 
00151       void 
00152       setTargetFeatures (const FeatureCloudConstPtr &features);
00153 
00155       inline FeatureCloudConstPtr const 
00156       getTargetFeatures () { return (target_features_); }
00157 
00161       void 
00162       setMinSampleDistance (float min_sample_distance) { min_sample_distance_ = min_sample_distance; }
00163 
00165       float 
00166       getMinSampleDistance () { return (min_sample_distance_); }
00167 
00171       void 
00172       setNumberOfSamples (int nr_samples) { nr_samples_ = nr_samples; }
00173 
00175       int 
00176       getNumberOfSamples () { return (nr_samples_); }
00177 
00182       void
00183       setCorrespondenceRandomness (int k) { k_correspondences_ = k; }
00184 
00186       int
00187       getCorrespondenceRandomness () { return (k_correspondences_); }
00188 
00193       void
00194       setErrorFunction (const boost::shared_ptr<ErrorFunctor> & error_functor) { error_functor_ = error_functor; }
00195 
00199       boost::shared_ptr<ErrorFunctor>
00200       getErrorFunction () { return (error_functor_); }
00201 
00202     protected:
00206       inline int 
00207       getRandomIndex (int n) { return (static_cast<int> (n * (rand () / (RAND_MAX + 1.0)))); };
00208       
00216       void 
00217       selectSamples (const PointCloudSource &cloud, int nr_samples, float min_sample_distance, 
00218                      std::vector<int> &sample_indices);
00219 
00227       void 
00228       findSimilarFeatures (const FeatureCloud &input_features, const std::vector<int> &sample_indices, 
00229                            std::vector<int> &corresponding_indices);
00230 
00235       float 
00236       computeErrorMetric (const PointCloudSource &cloud, float threshold);
00237 
00241       virtual void 
00242       computeTransformation (PointCloudSource &output, const Eigen::Matrix4f& guess);
00243 
00245       FeatureCloudConstPtr input_features_;
00246 
00248       FeatureCloudConstPtr target_features_;  
00249 
00251       int nr_samples_;
00252 
00254       float min_sample_distance_;
00255 
00257       int k_correspondences_;
00258      
00260       FeatureKdTreePtr feature_tree_;               
00261 
00263       boost::shared_ptr<ErrorFunctor> error_functor_;
00264     public:
00265       EIGEN_MAKE_ALIGNED_OPERATOR_NEW
00266   };
00267 }
00268 
00269 #include <pcl/registration/impl/ia_ransac.hpp>
00270 
00271 #endif  //#ifndef IA_RANSAC_H_


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