$search
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: pairwise_incremental_registration.cpp 36637 2011-04-20 01:33:25Z michael.s.dixon $ 00035 * 00036 */ 00037 00038 /* \author Radu Bogdan Rusu */ 00039 00040 #include <boost/make_shared.hpp> 00041 #include <ros/ros.h> 00042 #include <pcl/point_types.h> 00043 #include <pcl/point_cloud.h> 00044 #include <pcl/point_representation.h> 00045 00046 #include <pcl/io/pcd_io.h> 00047 #include <pcl/filters/voxel_grid.h> 00048 #include <pcl/features/normal_3d.h> 00049 #include <pcl/registration/icp.h> 00050 #include <pcl/registration/icp_nl.h> 00051 #include <pcl/registration/transforms.h> 00052 00053 #include "pcl_visualization/pcl_visualizer.h" 00054 00055 using namespace std; 00056 using pcl_visualization::PointCloudColorHandlerGenericField; 00057 using pcl_visualization::PointCloudColorHandlerCustom; 00058 00059 typedef pcl::PointXYZ PointT; 00060 typedef pcl::PointCloud<PointT> PointCloud; 00061 typedef pcl::PointNormal PointNormalT; 00062 typedef pcl::PointCloud<PointNormalT> PointCloudWithNormals; 00063 00064 // This is a tutorial so we can afford having global variables 00065 pcl_visualization::PCLVisualizer *p; 00066 int vp_1, vp_2; 00067 00068 struct PCD 00069 { 00070 PointCloud cloud; 00071 std::string f_name; 00072 }; 00073 00074 struct PCDComparator 00075 { 00076 bool operator () (const PCD& p1, const PCD& p2) 00077 { 00078 return (p1.f_name < p2.f_name); 00079 } 00080 }; 00081 00082 // Define a new point representation for < x, y, z, curvature > 00083 class MyPointRepresentation : public pcl::PointRepresentation <PointNormalT> 00084 { 00085 using pcl::PointRepresentation<PointNormalT>::nr_dimensions_; 00086 public: 00087 MyPointRepresentation () 00088 { 00089 // Define the number of dimensions 00090 nr_dimensions_ = 4; 00091 } 00092 00093 // Override the copyToFloatArray method to define our feature vector 00094 virtual void copyToFloatArray (const PointNormalT &p, float * out) const 00095 { 00096 // < x, y, z, curvature > 00097 out[0] = p.x; 00098 out[1] = p.y; 00099 out[2] = p.z; 00100 out[3] = p.curvature; 00101 } 00102 }; 00103 00105 00110 void 00111 loadData (int argc, char **argv, std::vector<PCD> &models) 00112 { 00113 std::string extension (".pcd"); 00114 // Suppose the first argument is the actual test model 00115 for (int i = 1; i < argc; i++) 00116 { 00117 string fname = string (argv[i]); 00118 // Needs to be at least 5: .plot 00119 if (fname.size () <= extension.size ()) 00120 continue; 00121 00122 transform (fname.begin (), fname.end (), fname.begin (), (int(*)(int))tolower); 00123 if (fname.compare (fname.size () - extension.size (), extension.size (), extension) == 0) 00124 { 00125 // Load the histogram model and saves it into the global list of models 00126 PCD m; 00127 m.f_name = argv[i]; 00128 pcl::io::loadPCDFile (argv[i], m.cloud); 00129 models.push_back (m); 00130 } 00131 } 00132 00133 //sort (models.begin (), models.end (), PCDComparator ()); 00134 } 00135 00137 00142 void 00143 pairAlign (const PointCloud &cloud_src, const PointCloud &cloud_tgt, PointCloud &output, bool downsample = false) 00144 { 00145 // 00146 // Downsample for consistency and speed 00147 // \note enable this for large datasets 00148 PointCloud src, tgt; 00149 pcl::VoxelGrid<PointT> grid; 00150 if (downsample) 00151 { 00152 grid.setLeafSize (0.001, 0.001, 0.001); 00153 grid.setFilterFieldName ("z"); // Assuming that "z" means distance from the sensor 00154 grid.setFilterLimits (-1, 5.0); 00155 00156 grid.setInputCloud (boost::make_shared<const PointCloud> (cloud_src)); 00157 grid.filter (src); 00158 00159 grid.setInputCloud (boost::make_shared<const PointCloud> (cloud_tgt)); 00160 grid.filter (tgt); 00161 } 00162 else 00163 { 00164 src = cloud_src; 00165 tgt = cloud_tgt; 00166 } 00167 00168 // 00169 // Compute surface normals and curvature 00170 PointCloudWithNormals points_with_normals_src, points_with_normals_tgt; 00171 00172 pcl::NormalEstimation<PointT, PointNormalT> norm_est; 00173 norm_est.setSearchMethod (boost::make_shared<pcl::KdTreeFLANN<PointT> > ()); 00174 norm_est.setKSearch (30); 00175 00176 norm_est.setInputCloud (boost::make_shared<const PointCloud> (src)); 00177 norm_est.compute (points_with_normals_src); 00178 pcl::copyPointCloud (src, points_with_normals_src); 00179 00180 norm_est.setInputCloud (boost::make_shared<const PointCloud> (tgt)); 00181 norm_est.compute (points_with_normals_tgt); 00182 pcl::copyPointCloud (tgt, points_with_normals_tgt); 00183 00184 // 00185 // Instantiate our custom point representation (defined above) ... 00186 MyPointRepresentation point_representation; 00187 // ... and weight the 'curvature' dimension so that it is balanced against x, y, and z 00188 float alpha[4] = {1.0, 1.0, 1.0, 1.0}; 00189 point_representation.setRescaleValues (alpha); 00190 00191 // 00192 // Align 00193 //pcl::IterativeClosestPoint<PointNormalT, PointNormalT> reg; 00194 pcl::IterativeClosestPointNonLinear<PointNormalT, PointNormalT> reg; 00195 reg.setTransformationEpsilon (1e-6); 00196 // Set the maximum distance between two correspondences (src<->tgt) to 10cm 00197 // Note: adjust this based on the size of your datasets 00198 reg.setMaxCorrespondenceDistance (0.1); 00199 // Set the point representation 00200 reg.setPointRepresentation (boost::make_shared<const MyPointRepresentation> (point_representation)); 00201 00202 reg.setInputCloud (boost::make_shared<const PointCloudWithNormals> (points_with_normals_src)); 00203 reg.setInputTarget (boost::make_shared<const PointCloudWithNormals> (points_with_normals_tgt)); 00204 00205 PointCloudWithNormals unused; 00206 //reg.align (unused); -- running the registration in a loop to visualize intermediate results 00207 00208 00209 PointCloudColorHandlerGenericField<PointNormalT> tgt_color_handler (points_with_normals_tgt, "curvature");//0, 255, 0); 00210 if (!tgt_color_handler.isCapable ()) 00211 ROS_WARN ("Cannot create curvature color handler!"); 00212 p->addPointCloud (points_with_normals_tgt, tgt_color_handler, "target", vp_2); 00213 PointCloudColorHandlerGenericField<PointNormalT> src_color_handler (points_with_normals_src, "curvature");//255, 0, 0); 00214 00215 // 00216 // Run the same optimization in a loop and visualize the results 00217 Eigen::Matrix4f Ti = Eigen::Matrix4f::Identity (), prev; 00218 PointCloudWithNormals reg_result = points_with_normals_src; 00219 reg.setMaximumIterations (2); 00220 for (int i = 0; i < 300; ++i) 00221 { 00222 // Visualize 00223 points_with_normals_src = reg_result; 00224 p->addPointCloud (points_with_normals_src, src_color_handler, "source", vp_2); 00225 00226 // Estimate 00227 reg.setInputCloud (boost::make_shared<const PointCloudWithNormals> (points_with_normals_src)); 00228 reg.align (reg_result); 00229 //if (!reg.hasConverged ()) 00230 // reg.setMaxCorrespondenceDistance (reg.getMaxCorrespondenceDistance () + 0.02); 00231 00232 Ti = reg.getFinalTransformation () * Ti; 00233 00234 /* // Break 00235 if (fabs ((reg.getLastIncrementalTransformation () - prev).sum ()) < reg.getTransformationEpsilon ()) 00236 { 00237 p->removePointCloud ("source"); 00238 break; 00239 }*/ 00240 00241 if (fabs ((reg.getLastIncrementalTransformation () - prev).sum ()) < reg.getTransformationEpsilon ()) 00242 reg.setMaxCorrespondenceDistance (reg.getMaxCorrespondenceDistance () - 0.001); 00243 00244 prev = reg.getLastIncrementalTransformation (); 00245 p->spinOnce (); p->removePointCloud ("source"); 00246 } 00247 p->removePointCloud ("target"); 00248 00249 // 00250 // Get transformation that aligns source to target 00251 //Eigen::Matrix4f T = reg.getFinalTransformation (); 00252 00253 // 00254 // Apply transformation to source and concatenate with target 00255 pcl::transformPointCloud (cloud_src, output, Ti); 00256 00257 PointCloudColorHandlerCustom<PointT> cloud_tgt_h (cloud_tgt, 0, 255, 0); 00258 PointCloudColorHandlerCustom<PointT> cloud_src_h (output, 255, 0, 0); 00259 p->addPointCloud (cloud_tgt, cloud_tgt_h, "target", vp_2); p->addPointCloud (output, cloud_src_h, "source", vp_2); p->spin (); p->removePointCloud ("source"); p->removePointCloud ("target"); 00260 00261 output += cloud_tgt; 00262 } 00263 00264 /* ---[ */ 00265 int 00266 main (int argc, char** argv) 00267 { 00268 vector<PCD> data; 00269 loadData (argc, argv, data); 00270 if (data.empty ()) 00271 { 00272 ROS_ERROR ("Syntax is: %s <source.pcd> <target.pcd> [*]", argv[0]); 00273 ROS_ERROR ("[*] - multiple files can be added. The registration results of (i, i+1) will be registered against (i+2), etc"); 00274 ROS_INFO ("Example: %s `rospack find pcl`/test/bun0.pcd `rospack find pcl`/test/bun4.pcd", argv[0]); 00275 return (-1); 00276 } 00277 ROS_INFO ("Loaded %d datasets.", (int)data.size ()); 00278 00279 00280 // Create a PCLVisualizer object 00281 p = new pcl_visualization::PCLVisualizer (argc, argv, "Pairwise Incremental Registration example"); 00282 p->createViewPort (0.0, 0, 0.5, 1.0, vp_1); 00283 p->createViewPort (0.5, 0, 1.0, 1.0, vp_2); 00284 00285 PointCloud result = data[0].cloud; 00286 for (size_t i = 1; i < data.size (); ++i) 00287 { 00288 // Add visualization data 00289 PointCloudColorHandlerCustom<PointT> tgt_h (data[i].cloud, 0, 255, 0); PointCloudColorHandlerCustom<PointT> src_h (result, 255, 0, 0); 00290 p->addPointCloud (data[i].cloud, tgt_h, "vp1_target", vp_1); p->addPointCloud (result, src_h, "vp1_source", vp_1); 00291 ROS_INFO ("Press q to begin the registration."); 00292 p->spin (); 00293 00294 PointCloud temp; 00295 ROS_INFO ("Aligning %s (%d) with %s (%d).", data[i-1].f_name.c_str (), (int)result.points.size (), data[i].f_name.c_str (), (int)data[i].cloud.points.size ()); 00296 pairAlign (result, data[i].cloud, temp); 00297 result = temp; 00298 00299 std::stringstream ss; 00300 ss << i << ".pcd"; 00301 pcl::io::savePCDFile (ss.str (), result, true); 00302 00303 // Remove visualization data 00304 p->removePointCloud ("vp1_target"); p->removePointCloud ("vp1_source"); 00305 } 00306 } 00307 /* ]--- */