outofcore_process.cpp
Go to the documentation of this file.
00001 /*
00002  * Software License Agreement (BSD License)
00003  *
00004  * Point Cloud Library (PCL) - www.pointclouds.org
00005  * Copyright (c) 2009-2012, Willow Garage, Inc.
00006  *
00007  * All rights reserved.
00008  *
00009  * Redistribution and use in source and binary forms, with or without
00010  * modification, are permitted provided that the following conditions
00011  * are met:
00012  *
00013  * * Redistributions of source code must retain the above copyright
00014  *   notice, this list of conditions and the following disclaimer.
00015  * * Redistributions in binary form must reproduce the above
00016  *   copyright notice, this list of conditions and the following
00017  *   disclaimer in the documentation and/or other materials provided
00018  *   with the distribution.
00019  * * Neither the name of Willow Garage, Inc. nor the names of its
00020  *   contributors may be used to endorse or promote products derived
00021  *   from this software without specific prior written permission.
00022  *
00023  * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
00024  * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
00025  * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
00026  * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
00027  * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
00028  * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
00029  * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
00030  * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
00031  * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
00032  * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
00033  * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
00034  * POSSIBILITY OF SUCH DAMAGE.
00035  *
00036  * $Id: outofcore_process.cpp 6927 2012-08-23 02:34:54Z stfox88 $
00037  * \author Justin Rosen
00038  * \author Stephen Fox
00039  */
00040 
00041 #include <pcl/common/time.h>
00042 #include <pcl/point_cloud.h>
00043 #include <pcl/point_types.h>
00044 #include <pcl/PCLPointCloud2.h>
00045 
00046 #include <pcl/io/pcd_io.h>
00047 #include <pcl/pcl_macros.h>
00048 
00049 #include <pcl/console/print.h>
00050 #include <pcl/console/parse.h>
00051 
00052 #include <pcl/outofcore/outofcore.h>
00053 #include <pcl/outofcore/outofcore_impl.h>
00054 
00055 // todo: Read clouds as PCLPointCloud2 so we don't need to define PointT explicitly.
00056 //       This also requires our octree to take PCLPointCloud2 as an input.
00057 typedef pcl::PointXYZ PointT;
00058 
00059 using namespace pcl;
00060 using namespace pcl::outofcore;
00061 
00062 using pcl::console::parse_argument;
00063 using pcl::console::parse_file_extension_argument;
00064 using pcl::console::find_switch;
00065 using pcl::console::print_error;
00066 using pcl::console::print_warn;
00067 using pcl::console::print_info;
00068 
00069 #include <boost/foreach.hpp>
00070 
00071 typedef OutofcoreOctreeBase<> octree_disk;
00072 
00073 const int OCTREE_DEPTH (0);
00074 const int OCTREE_RESOLUTION (1);
00075 
00076 PCLPointCloud2::Ptr
00077 getCloudFromFile (boost::filesystem::path pcd_path)
00078 {
00079   print_info ("Reading: %s ", pcd_path.c_str ());
00080 
00081 
00082   // Read PCD file
00083   PCLPointCloud2::Ptr cloud(new PCLPointCloud2);
00084 
00085   if (io::loadPCDFile (pcd_path.string (), *cloud) == -1)
00086   {
00087     PCL_ERROR ("Couldn't read file\n");
00088     exit (-1);
00089   }
00090 
00091   print_info ("(%d)\n", (cloud->width * cloud->height));
00092 
00093   return cloud;
00094 }
00095 
00096 int
00097 outofcoreProcess (std::vector<boost::filesystem::path> pcd_paths, boost::filesystem::path root_dir, 
00098                   int depth, double resolution, int build_octree_with, bool gen_lod, bool overwrite, bool multiresolution)
00099 {
00100   // Bounding box min/max pts
00101   PointT min_pt, max_pt;
00102 
00103   // Iterate over all pcd files resizing min/max
00104   for (size_t i = 0; i < pcd_paths.size (); i++)
00105   {
00106 
00107     // Get cloud
00108     PCLPointCloud2::Ptr cloud = getCloudFromFile (pcd_paths[i]);
00109     PointCloud<PointXYZ>::Ptr cloudXYZ (new PointCloud<PointXYZ>);
00110 
00111     fromPCLPointCloud2 (*cloud, *cloudXYZ);
00112 
00113     PointT tmp_min_pt, tmp_max_pt;
00114 
00115     if (i == 0)
00116     {
00117       // Get initial min/max
00118       getMinMax3D (*cloudXYZ, min_pt, max_pt);
00119     }
00120     else
00121     {
00122       getMinMax3D (*cloudXYZ, tmp_min_pt, tmp_max_pt);
00123 
00124       // Resize new min
00125       if (tmp_min_pt.x < min_pt.x)
00126         min_pt.x = tmp_min_pt.x;
00127       if (tmp_min_pt.y < min_pt.y)
00128         min_pt.y = tmp_min_pt.y;
00129       if (tmp_min_pt.z < min_pt.z)
00130         min_pt.z = tmp_min_pt.z;
00131 
00132       // Resize new max
00133       if (tmp_max_pt.x > max_pt.x)
00134         max_pt.x = tmp_max_pt.x;
00135       if (tmp_max_pt.y > max_pt.y)
00136         max_pt.y = tmp_max_pt.y;
00137       if (tmp_max_pt.z > max_pt.z)
00138         max_pt.z = tmp_max_pt.z;
00139     }
00140   }
00141 
00142   std::cout << "Bounds: " << min_pt << " - " << max_pt << std::endl;
00143 
00144   // The bounding box of the root node of the out-of-core octree must be specified
00145   const Eigen::Vector3d bounding_box_min (min_pt.x, min_pt.y, min_pt.z);
00146   const Eigen::Vector3d bounding_box_max (max_pt.x, max_pt.y, max_pt.z);
00147 
00148   //specify the directory and the root node's meta data file with a
00149   //".oct_idx" extension (currently it must be this extension)
00150   boost::filesystem::path octree_path_on_disk (root_dir / "tree.oct_idx");
00151 
00152   print_info ("Writing: %s\n", octree_path_on_disk.c_str ());
00153   //make sure there isn't an octree there already
00154   if (boost::filesystem::exists (octree_path_on_disk))
00155   {
00156     if (overwrite)
00157     {
00158       boost::filesystem::remove_all (root_dir);
00159     }
00160     else
00161     {
00162       PCL_ERROR ("There's already an octree in the default location. Check the tree directory\n");
00163       return (-1);
00164     }
00165   }
00166 
00167   octree_disk *outofcore_octree;
00168 
00169   //create the out-of-core data structure (typedef'd above)
00170   if (build_octree_with == OCTREE_DEPTH)
00171   {
00172     outofcore_octree = new octree_disk (depth, bounding_box_min, bounding_box_max, octree_path_on_disk, "ECEF");
00173   }
00174   else
00175   {
00176     outofcore_octree = new octree_disk (bounding_box_min, bounding_box_max, resolution, octree_path_on_disk, "ECEF");
00177   }
00178 
00179   uint64_t total_pts = 0;
00180 
00181   // Iterate over all pcd files adding points to the octree
00182   for (size_t i = 0; i < pcd_paths.size (); i++)
00183   {
00184 
00185     PCLPointCloud2::Ptr cloud = getCloudFromFile (pcd_paths[i]);
00186 
00187     boost::uint64_t pts = 0;
00188     
00189     if (gen_lod && !multiresolution)
00190     {
00191       print_info ("  Generating LODs\n");
00192       pts = outofcore_octree->addPointCloud_and_genLOD (cloud);
00193     }
00194     else
00195     {
00196       pts = outofcore_octree->addPointCloud (cloud, false);
00197     }
00198     
00199     print_info ("Successfully added %lu points\n", pts);
00200     print_info ("%lu Points were dropped (probably NaN)\n", cloud->width*cloud->height - pts);
00201     
00202 //    assert ( pts == cloud->width * cloud->height );
00203     
00204     total_pts += pts;
00205   }
00206 
00207   print_info ("Added a total of %lu from %d clouds\n",total_pts, pcd_paths.size ());
00208   
00209 
00210   double x, y;
00211   outofcore_octree->getBinDimension (x, y);
00212 
00213   print_info ("  Depth: %i\n", outofcore_octree->getDepth ());
00214   print_info ("  Resolution: [%f, %f]\n", x, y);
00215 
00216   if(multiresolution)
00217   {
00218     print_info ("Generating LOD...\n");
00219     outofcore_octree->setSamplePercent (0.25);
00220     outofcore_octree->buildLOD ();
00221   }
00222 
00223   //free outofcore data structure; the destructor forces buffer flush to disk
00224   delete outofcore_octree;
00225 
00226   return 0;
00227 }
00228 
00229 void
00230 printHelp (int, char **argv)
00231 {
00232   print_info ("This program is used to process pcd fiels into an outofcore data structure viewable by the");
00233   print_info ("pcl_outofcore_viewer\n\n");
00234   print_info ("%s <options> <input>.pcd <output_tree_dir>\n", argv[0]);
00235   print_info ("\n");
00236   print_info ("Options:\n");
00237   print_info ("\t -depth <resolution>           \t Octree depth\n");
00238   print_info ("\t -resolution <resolution>      \t Octree resolution\n");
00239   print_info ("\t -gen_lod                      \t Generate octree LODs\n");
00240   print_info ("\t -overwrite                    \t Overwrite existing octree\n");
00241   print_info ("\t -multiresolution              \t Generate multiresolutoin LOD\n");
00242   print_info ("\t -h                            \t Display help\n");
00243   print_info ("\n");
00244 }
00245 
00246 int
00247 main (int argc, char* argv[])
00248 {
00249   // Check for help (-h) flag
00250   if (argc > 1)
00251   {
00252     if (find_switch (argc, argv, "-h"))
00253     {
00254       printHelp (argc, argv);
00255       return (-1);
00256     }
00257   }
00258 
00259   // If no arguments specified
00260   if (argc - 1 < 1)
00261   {
00262     printHelp (argc, argv);
00263     return (-1);
00264   }
00265 
00266   if (find_switch (argc, argv, "-debug"))
00267   {
00268     pcl::console::setVerbosityLevel ( pcl::console::L_DEBUG );
00269   }
00270   
00271   // Defaults
00272   int depth = 4;
00273   double resolution = .1;
00274   bool gen_lod = false;
00275   bool multiresolution = false;
00276   bool overwrite = false;
00277   int build_octree_with = OCTREE_DEPTH;
00278 
00279   // If both depth and resolution specified
00280   if (find_switch (argc, argv, "-depth") && find_switch (argc, argv, "-resolution"))
00281   {
00282     PCL_ERROR ("Both -depth and -resolution specified, please specify one (Mutually exclusive)\n");
00283   }
00284   // Just resolution specified (Update how we build the tree)
00285   else if (find_switch (argc, argv, "-resolution"))
00286   {
00287     build_octree_with = OCTREE_RESOLUTION;
00288   }
00289 
00290   // Parse options
00291   parse_argument (argc, argv, "-depth", depth);
00292   parse_argument (argc, argv, "-resolution", resolution);
00293   gen_lod = find_switch (argc, argv, "-gen_lod");
00294   overwrite = find_switch (argc, argv, "-overwrite");
00295 
00296   if (gen_lod && find_switch (argc, argv, "-multiresolution"))
00297   {
00298     multiresolution = true;
00299   }
00300   
00301 
00302   // Parse non-option arguments for pcd files
00303   std::vector<int> file_arg_indices = parse_file_extension_argument (argc, argv, ".pcd");
00304 
00305   std::vector<boost::filesystem::path> pcd_paths;
00306   for (size_t i = 0; i < file_arg_indices.size (); i++)
00307   {
00308     boost::filesystem::path pcd_path (argv[file_arg_indices[i]]);
00309     if (!boost::filesystem::exists (pcd_path))
00310     {
00311       PCL_WARN ("File %s doesn't exist", pcd_path.string ().c_str ());
00312       continue;
00313     }
00314     pcd_paths.push_back (pcd_path);
00315 
00316   }
00317 
00318   // Check if we should process any files
00319   if (pcd_paths.size () < 1)
00320   {
00321     PCL_ERROR ("No .pcd files specified\n");
00322     return -1;
00323   }
00324 
00325   // Get root directory
00326   boost::filesystem::path root_dir (argv[argc - 1]);
00327 
00328   // Check if a root directory was specified, use directory of pcd file
00329   if (root_dir.extension () == ".pcd")
00330     root_dir = root_dir.parent_path () / (root_dir.stem().string() + "_tree").c_str();
00331 
00332   return outofcoreProcess (pcd_paths, root_dir, depth, resolution, build_octree_with, gen_lod, overwrite, multiresolution);
00333 }


pcl
Author(s): Open Perception
autogenerated on Wed Aug 26 2015 15:27:30