Point Cloud Library (PCL)
1.3.1
|
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: icp.h 2515 2011-09-19 13:40:11Z jspricke $ 00035 * 00036 */ 00037 00038 #ifndef PCL_ICP_H_ 00039 #define PCL_ICP_H_ 00040 00041 // PCL includes 00042 #include <pcl/sample_consensus/ransac.h> 00043 #include <pcl/sample_consensus/sac_model_registration.h> 00044 #include "pcl/registration/registration.h" 00045 #include "pcl/registration/transformation_estimation_svd.h" 00046 00047 namespace pcl 00048 { 00087 template <typename PointSource, typename PointTarget> 00088 class IterativeClosestPoint : public Registration<PointSource, PointTarget> 00089 { 00090 typedef typename Registration<PointSource, PointTarget>::PointCloudSource PointCloudSource; 00091 typedef typename PointCloudSource::Ptr PointCloudSourcePtr; 00092 typedef typename PointCloudSource::ConstPtr PointCloudSourceConstPtr; 00093 00094 typedef typename Registration<PointSource, PointTarget>::PointCloudTarget PointCloudTarget; 00095 00096 typedef PointIndices::Ptr PointIndicesPtr; 00097 typedef PointIndices::ConstPtr PointIndicesConstPtr; 00098 00099 public: 00101 IterativeClosestPoint () 00102 { 00103 reg_name_ = "IterativeClosestPoint"; 00104 transformation_estimation_.reset (new pcl::registration::TransformationEstimationSVD<PointSource, PointTarget>); 00105 }; 00106 00107 protected: 00111 virtual void 00112 computeTransformation (PointCloudSource &output); 00113 00118 virtual void 00119 computeTransformation (PointCloudSource &output, const Eigen::Matrix4f &guess); 00120 00121 using Registration<PointSource, PointTarget>::reg_name_; 00122 using Registration<PointSource, PointTarget>::getClassName; 00123 using Registration<PointSource, PointTarget>::input_; 00124 using Registration<PointSource, PointTarget>::indices_; 00125 using Registration<PointSource, PointTarget>::target_; 00126 using Registration<PointSource, PointTarget>::nr_iterations_; 00127 using Registration<PointSource, PointTarget>::max_iterations_; 00128 using Registration<PointSource, PointTarget>::previous_transformation_; 00129 using Registration<PointSource, PointTarget>::final_transformation_; 00130 using Registration<PointSource, PointTarget>::transformation_; 00131 using Registration<PointSource, PointTarget>::transformation_epsilon_; 00132 using Registration<PointSource, PointTarget>::converged_; 00133 using Registration<PointSource, PointTarget>::corr_dist_threshold_; 00134 using Registration<PointSource, PointTarget>::inlier_threshold_; 00135 using Registration<PointSource, PointTarget>::min_number_correspondences_; 00136 using Registration<PointSource, PointTarget>::update_visualizer_; 00137 using Registration<PointSource, PointTarget>::correspondence_distances_; 00138 using Registration<PointSource, PointTarget>::euclidean_fitness_epsilon_; 00139 using Registration<PointSource, PointTarget>::transformation_estimation_; 00140 }; 00141 } 00142 00143 #include "pcl/registration/impl/icp.hpp" 00144 00145 #endif //#ifndef PCL_ICP_H_