Go to the documentation of this file.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 #include <pcl/console/parse.h>
00037 #include <pcl/io/pcd_io.h>
00038 #include <pcl/point_types.h>
00039 #include <pcl/registration/ndt.h>
00040 #include <pcl/filters/approximate_voxel_grid.h>
00041 
00042 #include <string>
00043 #include <iostream>
00044 #include <fstream>
00045 #include <vector>
00046 
00047 
00048 typedef pcl::PointXYZ PointType;
00049 typedef pcl::PointCloud<PointType> Cloud;
00050 typedef Cloud::ConstPtr CloudConstPtr;
00051 typedef Cloud::Ptr CloudPtr;
00052 
00053 
00054 int
00055 main (int argc, char **argv)
00056 {
00057 
00058   int iter = 35;
00059   pcl::console::parse_argument (argc, argv, "-i", iter);
00060 
00061   float ndt_res = 1.0f;
00062   pcl::console::parse_argument (argc, argv, "-r", ndt_res);
00063 
00064   double step_size = 0.1;
00065   pcl::console::parse_argument (argc, argv, "-s", step_size);
00066 
00067   double trans_eps = 0.01;
00068   pcl::console::parse_argument (argc, argv, "-t", trans_eps);
00069 
00070   float filter_res = 0.2f;
00071   pcl::console::parse_argument (argc, argv, "-f", filter_res);
00072 
00073   bool display_help = false;
00074   pcl::console::parse_argument (argc, argv, "--help", display_help);
00075 
00076   if (display_help || argc <= 1)
00077   {
00078     std::cout << "Usage: ndt3d [OPTION]... [FILE]..." << std::endl;
00079     std::cout << "Registers PCD files using 3D Normal Distributions Transform algorithm" << std::endl << std::endl;
00080     std::cout << "  -i          maximum number of iterations" << std::endl;
00081     std::cout << "  -r          resolution (in meters) of NDT grid" << std::endl;
00082     std::cout << "  -s          maximum step size (in meters) of newton optimizer" << std::endl;
00083     std::cout << "  -t          transformation epsilon used for termination condition" << std::endl;
00084     std::cout << "  -f          voxel filter resolution (in meters) used on source cloud" << std::endl;
00085     std::cout << "     --help   display this help and exit" << std::endl;
00086 
00087     return (0);
00088   }
00089 
00090   std::vector<int> pcd_indices;
00091   pcd_indices = pcl::console::parse_file_extension_argument (argc, argv, ".pcd");
00092 
00093   CloudPtr model (new Cloud);
00094   if (pcl::io::loadPCDFile (argv[pcd_indices[0]], *model) == -1)
00095   {
00096     std::cout << "Could not read file" << std::endl;
00097     return -1;
00098   }
00099   std::cout << argv[pcd_indices[0]] << " width: " << model->width << " height: " << model->height << std::endl;
00100 
00101   std::string result_filename (argv[pcd_indices[0]]);
00102   result_filename = result_filename.substr (result_filename.rfind ("/") + 1);
00103   pcl::io::savePCDFile (result_filename.c_str (), *model);
00104   std::cout << "saving first model to " << result_filename << std::endl;
00105 
00106   Eigen::Matrix4f t (Eigen::Matrix4f::Identity ());
00107 
00108   pcl::ApproximateVoxelGrid<PointType> voxel_filter;
00109   voxel_filter.setLeafSize (filter_res, filter_res, filter_res);
00110 
00111   for (size_t i = 1; i < pcd_indices.size (); i++)
00112   {
00113     CloudPtr data (new Cloud);
00114     if (pcl::io::loadPCDFile (argv[pcd_indices[i]], *data) == -1)
00115     {
00116       std::cout << "Could not read file" << std::endl;
00117       return -1;
00118     }
00119     std::cout << argv[pcd_indices[i]] << " width: " << data->width << " height: " << data->height << std::endl;
00120 
00121     pcl::NormalDistributionsTransform<PointType, PointType> * ndt = new pcl::NormalDistributionsTransform<PointType, PointType>();
00122 
00123     ndt->setMaximumIterations (iter);
00124     ndt->setResolution (ndt_res);
00125     ndt->setStepSize (step_size);
00126     ndt->setTransformationEpsilon (trans_eps);
00127 
00128     ndt->setInputTarget (model);
00129 
00130     CloudPtr filtered_data (new Cloud);
00131     voxel_filter.setInputCloud (data);
00132     voxel_filter.filter (*filtered_data);
00133 
00134     ndt->setInputSource (filtered_data);
00135 
00136     CloudPtr tmp (new Cloud);
00137     ndt->align (*tmp);
00138 
00139     t = t * ndt->getFinalTransformation ();
00140 
00141     pcl::transformPointCloud (*data, *tmp, t);
00142 
00143     std::cout << ndt->getFinalTransformation () << std::endl;
00144 
00145     *model = *data;
00146 
00147     std::string result_filename (argv[pcd_indices[i]]);
00148     result_filename = result_filename.substr (result_filename.rfind ("/") + 1);
00149     pcl::io::savePCDFileBinary (result_filename.c_str (), *tmp);
00150     std::cout << "saving result to " << result_filename << std::endl;
00151   }
00152 
00153   return (0);
00154 }