ndt3d.cpp
Go to the documentation of this file.
00001 /*
00002  * Software License Agreement (BSD License)
00003  *
00004  *  Copyright (c) 2011, 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 the copyright holder(s) 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  */
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 }


pcl
Author(s): Open Perception
autogenerated on Wed Aug 26 2015 15:25:44