xyz2pcd.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) 2012-, Open Perception, 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 the copyright holder(s) 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  */
00037 
00038 #include <pcl/io/pcd_io.h>
00039 #include <pcl/console/print.h>
00040 #include <pcl/console/parse.h>
00041 #include <pcl/console/time.h>
00042 
00043 using namespace std;
00044 using namespace pcl;
00045 using namespace pcl::io;
00046 using namespace pcl::console;
00047 
00048 void
00049 printHelp (int, char **argv)
00050 {
00051   print_error ("Syntax is: %s input.xyz output.pcd\n", argv[0]);
00052 }
00053 
00054 bool
00055 loadCloud (const string &filename, PointCloud<PointXYZ> &cloud)
00056 {
00057   ifstream fs;
00058   fs.open (filename.c_str (), ios::binary);
00059   if (!fs.is_open () || fs.fail ())
00060   {
00061     PCL_ERROR ("Could not open file '%s'! Error : %s\n", filename.c_str (), strerror (errno)); 
00062     fs.close ();
00063     return (false);
00064   }
00065   
00066   string line;
00067   vector<string> st;
00068 
00069   while (!fs.eof ())
00070   {
00071     getline (fs, line);
00072     // Ignore empty lines
00073     if (line == "")
00074       continue;
00075 
00076     // Tokenize the line
00077     boost::trim (line);
00078     boost::split (st, line, boost::is_any_of ("\t\r "), boost::token_compress_on);
00079 
00080     if (st.size () != 3)
00081       continue;
00082 
00083     cloud.push_back (PointXYZ (float (atof (st[0].c_str ())), float (atof (st[1].c_str ())), float (atof (st[2].c_str ()))));
00084   }
00085   fs.close ();
00086 
00087   cloud.width = uint32_t (cloud.size ()); cloud.height = 1; cloud.is_dense = true;
00088   return (true);
00089 }
00090 
00091 /* ---[ */
00092 int
00093 main (int argc, char** argv)
00094 {
00095   print_info ("Convert a simple XYZ file to PCD format. For more information, use: %s -h\n", argv[0]);
00096 
00097   if (argc < 3)
00098   {
00099     printHelp (argc, argv);
00100     return (-1);
00101   }
00102 
00103   // Parse the command line arguments for .pcd and .ply files
00104   vector<int> pcd_file_indices = parse_file_extension_argument (argc, argv, ".pcd");
00105   vector<int> xyz_file_indices = parse_file_extension_argument (argc, argv, ".xyz");
00106   if (pcd_file_indices.size () != 1 || xyz_file_indices.size () != 1)
00107   {
00108     print_error ("Need one input XYZ file and one output PCD file.\n");
00109     return (-1);
00110   }
00111 
00112   // Load the first file
00113   PointCloud<PointXYZ> cloud;
00114   if (!loadCloud (argv[xyz_file_indices[0]], cloud)) 
00115     return (-1);
00116 
00117   // Convert to PCD and save
00118   PCDWriter w;
00119   w.writeBinaryCompressed (argv[pcd_file_indices[0]], cloud);
00120 }
00121 


pcl
Author(s): Open Perception
autogenerated on Wed Aug 26 2015 15:38:43