00001
00002
00003
00004
00005
00006
00007
00008
00009
00010
00011
00012
00013
00014
00015
00016
00017
00018
00019
00020
00021
00022
00023
00024
00025
00026
00027
00028
00029
00030
00031
00032
00033
00034
00035
00036
00037
00038
00039
00040
00041 #include <boost/make_shared.hpp>
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
00048 #include <pcl/filters/voxel_grid.h>
00049 #include <pcl/filters/filter.h>
00050
00051 #include <pcl/features/normal_3d.h>
00052
00053 #include <pcl/registration/icp.h>
00054 #include <pcl/registration/icp_nl.h>
00055 #include <pcl/registration/transforms.h>
00056
00057 #include <pcl/visualization/pcl_visualizer.h>
00058
00059 using pcl::visualization::PointCloudColorHandlerGenericField;
00060 using pcl::visualization::PointCloudColorHandlerCustom;
00061
00062
00063 typedef pcl::PointXYZ PointT;
00064 typedef pcl::PointCloud<PointT> PointCloud;
00065 typedef pcl::PointNormal PointNormalT;
00066 typedef pcl::PointCloud<PointNormalT> PointCloudWithNormals;
00067
00068
00069
00070 pcl::visualization::PCLVisualizer *p;
00071
00072 int vp_1, vp_2;
00073
00074
00075 struct PCD
00076 {
00077 PointCloud::Ptr cloud;
00078 std::string f_name;
00079
00080 PCD() : cloud (new PointCloud) {};
00081 };
00082
00083 struct PCDComparator
00084 {
00085 bool operator () (const PCD& p1, const PCD& p2)
00086 {
00087 return (p1.f_name < p2.f_name);
00088 }
00089 };
00090
00091
00092
00093 class MyPointRepresentation : public pcl::PointRepresentation <PointNormalT>
00094 {
00095 using pcl::PointRepresentation<PointNormalT>::nr_dimensions_;
00096 public:
00097 MyPointRepresentation ()
00098 {
00099
00100 nr_dimensions_ = 4;
00101 }
00102
00103
00104 virtual void copyToFloatArray (const PointNormalT &p, float * out) const
00105 {
00106
00107 out[0] = p.x;
00108 out[1] = p.y;
00109 out[2] = p.z;
00110 out[3] = p.curvature;
00111 }
00112 };
00113
00114
00116
00119 void showCloudsLeft(const PointCloud::Ptr cloud_target, const PointCloud::Ptr cloud_source)
00120 {
00121 p->removePointCloud ("vp1_target");
00122 p->removePointCloud ("vp1_source");
00123
00124 PointCloudColorHandlerCustom<PointT> tgt_h (cloud_target, 0, 255, 0);
00125 PointCloudColorHandlerCustom<PointT> src_h (cloud_source, 255, 0, 0);
00126 p->addPointCloud (cloud_target, tgt_h, "vp1_target", vp_1);
00127 p->addPointCloud (cloud_source, src_h, "vp1_source", vp_1);
00128
00129 PCL_INFO ("Press q to begin the registration.\n");
00130 p-> spin();
00131 }
00132
00133
00135
00138 void showCloudsRight(const PointCloudWithNormals::Ptr cloud_target, const PointCloudWithNormals::Ptr cloud_source)
00139 {
00140 p->removePointCloud ("source");
00141 p->removePointCloud ("target");
00142
00143
00144 PointCloudColorHandlerGenericField<PointNormalT> tgt_color_handler (cloud_target, "curvature");
00145 if (!tgt_color_handler.isCapable ())
00146 PCL_WARN ("Cannot create curvature color handler!");
00147
00148 PointCloudColorHandlerGenericField<PointNormalT> src_color_handler (cloud_source, "curvature");
00149 if (!src_color_handler.isCapable ())
00150 PCL_WARN ("Cannot create curvature color handler!");
00151
00152
00153 p->addPointCloud (cloud_target, tgt_color_handler, "target", vp_2);
00154 p->addPointCloud (cloud_source, src_color_handler, "source", vp_2);
00155
00156 p->spinOnce();
00157 }
00158
00160
00165 void loadData (int argc, char **argv, std::vector<PCD, Eigen::aligned_allocator<PCD> > &models)
00166 {
00167 std::string extension (".pcd");
00168
00169 for (int i = 1; i < argc; i++)
00170 {
00171 std::string fname = std::string (argv[i]);
00172
00173 if (fname.size () <= extension.size ())
00174 continue;
00175
00176 std::transform (fname.begin (), fname.end (), fname.begin (), (int(*)(int))tolower);
00177
00178
00179 if (fname.compare (fname.size () - extension.size (), extension.size (), extension) == 0)
00180 {
00181
00182 PCD m;
00183 m.f_name = argv[i];
00184 pcl::io::loadPCDFile (argv[i], *m.cloud);
00185
00186 std::vector<int> indices;
00187 pcl::removeNaNFromPointCloud(*m.cloud,*m.cloud, indices);
00188
00189 models.push_back (m);
00190 }
00191 }
00192 }
00193
00194
00196
00202 void pairAlign (const PointCloud::Ptr cloud_src, const PointCloud::Ptr cloud_tgt, PointCloud::Ptr output, Eigen::Matrix4f &final_transform, bool downsample = false)
00203 {
00204
00205
00206
00207 PointCloud::Ptr src (new PointCloud);
00208 PointCloud::Ptr tgt (new PointCloud);
00209 pcl::VoxelGrid<PointT> grid;
00210 if (downsample)
00211 {
00212 grid.setLeafSize (0.05, 0.05, 0.05);
00213 grid.setInputCloud (cloud_src);
00214 grid.filter (*src);
00215
00216 grid.setInputCloud (cloud_tgt);
00217 grid.filter (*tgt);
00218 }
00219 else
00220 {
00221 src = cloud_src;
00222 tgt = cloud_tgt;
00223 }
00224
00225
00226
00227 PointCloudWithNormals::Ptr points_with_normals_src (new PointCloudWithNormals);
00228 PointCloudWithNormals::Ptr points_with_normals_tgt (new PointCloudWithNormals);
00229
00230 pcl::NormalEstimation<PointT, PointNormalT> norm_est;
00231 pcl::search::KdTree<pcl::PointXYZ>::Ptr tree (new pcl::search::KdTree<pcl::PointXYZ> ());
00232 norm_est.setSearchMethod (tree);
00233 norm_est.setKSearch (30);
00234
00235 norm_est.setInputCloud (src);
00236 norm_est.compute (*points_with_normals_src);
00237 pcl::copyPointCloud (*src, *points_with_normals_src);
00238
00239 norm_est.setInputCloud (tgt);
00240 norm_est.compute (*points_with_normals_tgt);
00241 pcl::copyPointCloud (*tgt, *points_with_normals_tgt);
00242
00243
00244
00245 MyPointRepresentation point_representation;
00246
00247 float alpha[4] = {1.0, 1.0, 1.0, 1.0};
00248 point_representation.setRescaleValues (alpha);
00249
00250
00251
00252 pcl::IterativeClosestPointNonLinear<PointNormalT, PointNormalT> reg;
00253 reg.setTransformationEpsilon (1e-6);
00254
00255
00256 reg.setMaxCorrespondenceDistance (0.1);
00257
00258 reg.setPointRepresentation (boost::make_shared<const MyPointRepresentation> (point_representation));
00259
00260 reg.setInputCloud (points_with_normals_src);
00261 reg.setInputTarget (points_with_normals_tgt);
00262
00263
00264
00265
00266
00267 Eigen::Matrix4f Ti = Eigen::Matrix4f::Identity (), prev, targetToSource;
00268 PointCloudWithNormals::Ptr reg_result = points_with_normals_src;
00269 reg.setMaximumIterations (2);
00270 for (int i = 0; i < 30; ++i)
00271 {
00272 PCL_INFO ("Iteration Nr. %d.\n", i);
00273
00274
00275 points_with_normals_src = reg_result;
00276
00277
00278 reg.setInputCloud (points_with_normals_src);
00279 reg.align (*reg_result);
00280
00281
00282 Ti = reg.getFinalTransformation () * Ti;
00283
00284
00285
00286
00287 if (fabs ((reg.getLastIncrementalTransformation () - prev).sum ()) < reg.getTransformationEpsilon ())
00288 reg.setMaxCorrespondenceDistance (reg.getMaxCorrespondenceDistance () - 0.001);
00289
00290 prev = reg.getLastIncrementalTransformation ();
00291
00292
00293 showCloudsRight(points_with_normals_tgt, points_with_normals_src);
00294 }
00295
00296
00297
00298 targetToSource = Ti.inverse();
00299
00300
00301
00302 pcl::transformPointCloud (*cloud_tgt, *output, targetToSource);
00303
00304 p->removePointCloud ("source");
00305 p->removePointCloud ("target");
00306
00307 PointCloudColorHandlerCustom<PointT> cloud_tgt_h (output, 0, 255, 0);
00308 PointCloudColorHandlerCustom<PointT> cloud_src_h (cloud_src, 255, 0, 0);
00309 p->addPointCloud (output, cloud_tgt_h, "target", vp_2);
00310 p->addPointCloud (cloud_src, cloud_src_h, "source", vp_2);
00311
00312 PCL_INFO ("Press q to continue the registration.\n");
00313 p->spin ();
00314
00315 p->removePointCloud ("source");
00316 p->removePointCloud ("target");
00317
00318
00319 *output += *cloud_src;
00320
00321 final_transform = targetToSource;
00322 }
00323
00324
00325
00326 int main (int argc, char** argv)
00327 {
00328
00329 std::vector<PCD, Eigen::aligned_allocator<PCD> > data;
00330 loadData (argc, argv, data);
00331
00332
00333 if (data.empty ())
00334 {
00335 PCL_ERROR ("Syntax is: %s <source.pcd> <target.pcd> [*]", argv[0]);
00336 PCL_ERROR ("[*] - multiple files can be added. The registration results of (i, i+1) will be registered against (i+2), etc");
00337 return (-1);
00338 }
00339 PCL_INFO ("Loaded %d datasets.", (int)data.size ());
00340
00341
00342 p = new pcl::visualization::PCLVisualizer (argc, argv, "Pairwise Incremental Registration example");
00343 p->createViewPort (0.0, 0, 0.5, 1.0, vp_1);
00344 p->createViewPort (0.5, 0, 1.0, 1.0, vp_2);
00345
00346 PointCloud::Ptr result (new PointCloud), source, target;
00347 Eigen::Matrix4f GlobalTransform = Eigen::Matrix4f::Identity (), pairTransform;
00348
00349 for (size_t i = 1; i < data.size (); ++i)
00350 {
00351 source = data[i-1].cloud;
00352 target = data[i].cloud;
00353
00354
00355 showCloudsLeft(source, target);
00356
00357 PointCloud::Ptr temp (new PointCloud);
00358 PCL_INFO ("Aligning %s (%d) with %s (%d).\n", data[i-1].f_name.c_str (), source->points.size (), data[i].f_name.c_str (), target->points.size ());
00359 pairAlign (source, target, temp, pairTransform, true);
00360
00361
00362 pcl::transformPointCloud (*temp, *result, GlobalTransform);
00363
00364
00365 GlobalTransform = pairTransform * GlobalTransform;
00366
00367
00368 std::stringstream ss;
00369 ss << i << ".pcd";
00370 pcl::io::savePCDFile (ss.str (), *result, true);
00371
00372 }
00373 }
00374