concatenate_points_pcd.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) 2010, Willow Garage, Inc.
00006  *  Copyright (c) 2012-, Open Perception, Inc.
00007  *
00008  *  All rights reserved.
00009  *
00010  *  Redistribution and use in source and binary forms, with or without
00011  *  modification, are permitted provided that the following conditions
00012  *  are met:
00013  *
00014  *   * Redistributions of source code must retain the above copyright
00015  *     notice, this list of conditions and the following disclaimer.
00016  *   * Redistributions in binary form must reproduce the above
00017  *     copyright notice, this list of conditions and the following
00018  *     disclaimer in the documentation and/or other materials provided
00019  *     with the distribution.
00020  *   * Neither the name of the copyright holder(s) nor the names of its
00021  *     contributors may be used to endorse or promote products derived
00022  *     from this software without specific prior written permission.
00023  *
00024  *  THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
00025  *  "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
00026  *  LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
00027  *  FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
00028  *  COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
00029  *  INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
00030  *  BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
00031  *  LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
00032  *  CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
00033  *  LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
00034  *  ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
00035  *  POSSIBILITY OF SUCH DAMAGE.
00036  *
00037  * $Id$
00038  *
00039  */
00040 
00047 #include <iostream>
00048 #include <pcl/console/time.h>
00049 #include <pcl/io/pcd_io.h>
00050 #include <pcl/point_types.h>
00051 
00052 Eigen::Vector4f    translation;
00053 Eigen::Quaternionf orientation;
00054 
00056 
00062 std::vector<int>
00063 parseFileExtensionArgument (int argc, char** argv, std::string extension)
00064 {
00065   std::vector<int> indices;
00066   for (int i = 1; i < argc; ++i)
00067   {
00068     std::string fname = std::string (argv[i]);
00069     
00070     // Needs to be at least 4: .ext
00071     if (fname.size () <= 4)
00072       continue;
00073     
00074     // For being case insensitive
00075     std::transform (fname.begin (), fname.end (), fname.begin (), tolower);
00076     std::transform (extension.begin (), extension.end (), extension.begin (), tolower);
00077     
00078     // Check if found
00079     std::string::size_type it;
00080     if ((it = fname.find (extension)) != std::string::npos)
00081     {
00082       // Additional check: we want to be able to differentiate between .p and .png
00083       if ((extension.size () - (fname.size () - it)) == 0)
00084         indices.push_back (i);
00085     }
00086   }
00087   return (indices);
00088 }
00089 
00090 bool
00091 loadCloud (const std::string &filename, pcl::PCLPointCloud2 &cloud)
00092 {
00093   using namespace pcl::console;
00094   TicToc tt;
00095   print_highlight ("Loading "); print_value ("%s ", filename.c_str ());
00096 
00097   tt.tic ();
00098   if (pcl::io::loadPCDFile (filename, cloud, translation, orientation) < 0)
00099     return (false);
00100   print_info ("[done, "); print_value ("%g", tt.toc ()); print_info (" ms : "); print_value ("%d", cloud.width * cloud.height); print_info (" points]\n");
00101   print_info ("Available dimensions: "); print_value ("%s\n", pcl::getFieldsList (cloud).c_str ());
00102 
00103   return (true);
00104 }
00105 
00106 void
00107 saveCloud (const std::string &filename, const pcl::PCLPointCloud2 &output)
00108 {
00109   using namespace pcl::console;
00110   TicToc tt;
00111   tt.tic ();
00112 
00113   print_highlight ("Saving "); print_value ("%s ", filename.c_str ());
00114 
00115   pcl::PCDWriter w;
00116   w.writeBinaryCompressed (filename, output, translation, orientation);
00117   
00118   print_info ("[done, "); print_value ("%g", tt.toc ()); print_info (" ms : "); print_value ("%d", output.width * output.height); print_info (" points]\n");
00119 }
00120 
00121 
00122 /* ---[ */
00123 int
00124 main (int argc, char** argv)
00125 {
00126   if (argc < 2)
00127   {
00128     std::cerr << "Syntax is: " << argv[0] << " <filename 1..N.pcd>" << std::endl;
00129     std::cerr << "Result will be saved to output.pcd" << std::endl;
00130     return (-1);
00131   }
00132 
00133   std::vector<int> file_indices = parseFileExtensionArgument (argc, argv, ".pcd");
00134 
00135   //pcl::PointCloud<pcl::PointXYZ> cloud_all;
00136   pcl::PCLPointCloud2 cloud_all;
00137   for (size_t i = 0; i < file_indices.size (); ++i)
00138   {
00139     // Load the Point Cloud
00140     pcl::PCLPointCloud2 cloud;
00141     loadCloud (argv[file_indices[i]], cloud);
00142     //pcl::PointCloud<pcl::PointXYZ> cloud;
00143     //pcl::io::loadPCDFile (argv[file_indices[i]], cloud);
00144     //cloud_all += cloud;
00145     pcl::concatenatePointCloud (cloud_all, cloud, cloud_all);
00146     PCL_INFO ("Total number of points so far: %u. Total data size: %zu bytes.\n", cloud_all.width * cloud_all.height, cloud_all.data.size ());
00147   }
00148 
00149   saveCloud ("output.pcd", cloud_all);
00150   
00151   return (0);
00152 }
00153 /* ]--- */


pcl
Author(s): Open Perception
autogenerated on Wed Aug 26 2015 15:22:51