correspondence_estimation_normal_shooting.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  *  Copyright (c) 2012-, Open Perception, Inc.
00007  *
00008  *  All rights reserved.
00009  *
00010  *  Redistribution and use in source and binary forms, with or without
00011  *  modification, are permitted provided that the following conditions
00012  *  are met:
00013  *
00014  *   * Redistributions of source code must retain the above copyright
00015  *     notice, this list of conditions and the following disclaimer.
00016  *   * Redistributions in binary form must reproduce the above
00017  *     copyright notice, this list of conditions and the following
00018  *     disclaimer in the documentation and/or other materials provided
00019  *     with the distribution.
00020  *   * Neither the name of the copyright holder(s) nor the names of its
00021  *     contributors may be used to endorse or promote products derived
00022  *     from this software without specific prior written permission.
00023  *
00024  *  THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
00025  *  "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
00026  *  LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
00027  *  FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
00028  *  COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
00029  *  INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
00030  *  BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
00031  *  LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
00032  *  CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
00033  *  LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
00034  *  ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
00035  *  POSSIBILITY OF SUCH DAMAGE.
00036  *
00037  * $Id$
00038  *
00039  */
00040 
00041 #ifndef PCL_REGISTRATION_CORRESPONDENCE_ESTIMATION_NORMAL_SHOOTING_H_
00042 #define PCL_REGISTRATION_CORRESPONDENCE_ESTIMATION_NORMAL_SHOOTING_H_
00043 
00044 #include <pcl/registration/correspondence_types.h>
00045 #include <pcl/registration/correspondence_estimation.h>
00046 
00047 namespace pcl
00048 {
00049   namespace registration
00050   {
00077     template <typename PointSource, typename PointTarget, typename NormalT, typename Scalar = float>
00078     class CorrespondenceEstimationNormalShooting : public CorrespondenceEstimationBase<PointSource, PointTarget, Scalar>
00079     {
00080       public:
00081         typedef boost::shared_ptr<CorrespondenceEstimationNormalShooting<PointSource, PointTarget, NormalT, Scalar> > Ptr;
00082         typedef boost::shared_ptr<const CorrespondenceEstimationNormalShooting<PointSource, PointTarget, NormalT, Scalar> > ConstPtr;
00083 
00084         using CorrespondenceEstimationBase<PointSource, PointTarget, Scalar>::initCompute;
00085         using CorrespondenceEstimationBase<PointSource, PointTarget, Scalar>::initComputeReciprocal;
00086         using CorrespondenceEstimationBase<PointSource, PointTarget, Scalar>::input_transformed_;
00087         using PCLBase<PointSource>::deinitCompute;
00088         using PCLBase<PointSource>::input_;
00089         using PCLBase<PointSource>::indices_;
00090         using CorrespondenceEstimationBase<PointSource, PointTarget, Scalar>::getClassName;
00091         using CorrespondenceEstimationBase<PointSource, PointTarget, Scalar>::point_representation_;
00092         using CorrespondenceEstimationBase<PointSource, PointTarget, Scalar>::target_indices_;
00093 
00094         typedef typename pcl::search::KdTree<PointTarget> KdTree;
00095         typedef typename pcl::search::KdTree<PointTarget>::Ptr KdTreePtr;
00096 
00097         typedef pcl::PointCloud<PointSource> PointCloudSource;
00098         typedef typename PointCloudSource::Ptr PointCloudSourcePtr;
00099         typedef typename PointCloudSource::ConstPtr PointCloudSourceConstPtr;
00100 
00101         typedef pcl::PointCloud<PointTarget> PointCloudTarget;
00102         typedef typename PointCloudTarget::Ptr PointCloudTargetPtr;
00103         typedef typename PointCloudTarget::ConstPtr PointCloudTargetConstPtr;
00104 
00105         typedef pcl::PointCloud<NormalT> PointCloudNormals;
00106         typedef typename PointCloudNormals::Ptr NormalsPtr;
00107         typedef typename PointCloudNormals::ConstPtr NormalsConstPtr;
00108 
00114         CorrespondenceEstimationNormalShooting ()
00115           : source_normals_ ()
00116           , source_normals_transformed_ ()
00117           , k_ (10)
00118         {
00119           corr_name_ = "CorrespondenceEstimationNormalShooting";
00120         }
00121 
00123         virtual ~CorrespondenceEstimationNormalShooting () {}
00124 
00128         inline void
00129         setSourceNormals (const NormalsConstPtr &normals) { source_normals_ = normals; }
00130 
00133         inline NormalsConstPtr
00134         getSourceNormals () const { return (source_normals_); }
00135 
00141         void 
00142         determineCorrespondences (pcl::Correspondences &correspondences,
00143                                   double max_distance = std::numeric_limits<double>::max ());
00144 
00152         virtual void 
00153         determineReciprocalCorrespondences (pcl::Correspondences &correspondences,
00154                                             double max_distance = std::numeric_limits<double>::max ());
00155 
00161         inline void
00162         setKSearch (unsigned int k) { k_ = k; }
00163 
00168         inline void
00169         getKSearch () const { return (k_); }
00170 
00171       protected:
00172 
00173         using CorrespondenceEstimationBase<PointSource, PointTarget, Scalar>::corr_name_;
00174         using CorrespondenceEstimationBase<PointSource, PointTarget, Scalar>::tree_;
00175         using CorrespondenceEstimationBase<PointSource, PointTarget, Scalar>::tree_reciprocal_;
00176         using CorrespondenceEstimationBase<PointSource, PointTarget, Scalar>::target_;
00177 
00179         bool
00180         initCompute ();
00181 
00182        private:
00183 
00185         NormalsConstPtr source_normals_;
00186 
00188         NormalsPtr source_normals_transformed_;
00189 
00191         unsigned int k_;
00192     };
00193   }
00194 }
00195 
00196 #include <pcl/registration/impl/correspondence_estimation_normal_shooting.hpp>
00197 
00198 #endif /* PCL_REGISTRATION_CORRESPONDENCE_ESTIMATION_NORMAL_SHOOTING_H_ */


pcl
Author(s): Open Perception
autogenerated on Wed Aug 26 2015 15:23:00