ply2ply.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) 2007-2012, Ares Lagae
00006  *  Copyright (c) 2012, Willow Garage, Inc.
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: ply2ply.cpp 4918 2012-03-05 17:41:10Z nizar $
00037  *
00038  */
00039 
00040 #include <cstdlib>
00041 #include <cstring>
00042 #include <fstream>
00043 #include <iostream>
00044 
00045 #include <boost/bind.hpp>
00046 
00047 #include <pcl/io/ply/ply_parser.h>
00048 
00057 class ply_to_ply_converter
00058 {
00059   public:
00060     typedef int format_type;
00061     enum format
00062     {
00063       same_format,
00064       ascii_format,
00065       binary_format,
00066       binary_big_endian_format,
00067       binary_little_endian_format
00068     };
00069   
00070     ply_to_ply_converter(format_type format) : 
00071       format_(format), input_format_(), output_format_(), 
00072       bol_ (), ostream_ () {}
00073 
00074     bool 
00075     convert(std::istream& istream, std::ostream& ostream);
00076 
00077   private:
00078     void
00079     info_callback(const std::string& filename, std::size_t line_number, const std::string& message);
00080     
00081     void
00082     warning_callback(const std::string& filename, std::size_t line_number, const std::string& message);
00083     
00084     void
00085     error_callback(const std::string& filename, std::size_t line_number, const std::string& message);
00086     
00087     void
00088     magic_callback();
00089     
00090     void
00091     format_callback(pcl::io::ply::format_type format, const std::string& version);
00092     
00093     void
00094     element_begin_callback();
00095     
00096     void
00097     element_end_callback();
00098 
00099     boost::tuple<boost::function<void()>, boost::function<void()> > 
00100     element_definition_callback(const std::string& element_name, std::size_t count);
00101 
00102     template <typename ScalarType> void
00103     scalar_property_callback(ScalarType scalar);
00104 
00105     template <typename ScalarType> boost::function<void (ScalarType)> 
00106     scalar_property_definition_callback(const std::string& element_name, const std::string& property_name);
00107 
00108     template <typename SizeType, typename ScalarType> void
00109     list_property_begin_callback(SizeType size);
00110 
00111     template <typename SizeType, typename ScalarType> void
00112     list_property_element_callback(ScalarType scalar);
00113 
00114     template <typename SizeType, typename ScalarType> void
00115     list_property_end_callback();
00116 
00117     template <typename SizeType, typename ScalarType> boost::tuple<boost::function<void (SizeType)>, 
00118                                                                       boost::function<void (ScalarType)>, 
00119                                                                       boost::function<void ()> > 
00120     list_property_definition_callback(const std::string& element_name, const std::string& property_name);
00121     
00122     void
00123     comment_callback(const std::string& comment);
00124     
00125     void
00126     obj_info_callback(const std::string& obj_info);
00127 
00128     bool 
00129     end_header_callback();
00130 
00131     format_type format_;
00132     pcl::io::ply::format_type input_format_, output_format_;
00133     bool bol_;
00134     std::ostream* ostream_;
00135 };
00136 
00137 void
00138 ply_to_ply_converter::info_callback(const std::string& filename, std::size_t line_number, const std::string& message)
00139 {
00140   std::cerr << filename << ":" << line_number << ": " << "info: " << message << std::endl;
00141 }
00142 
00143 void
00144 ply_to_ply_converter::warning_callback(const std::string& filename, std::size_t line_number, const std::string& message)
00145 {
00146   std::cerr << filename << ":" << line_number << ": " << "warning: " << message << std::endl;
00147 }
00148 
00149 void
00150 ply_to_ply_converter::error_callback(const std::string& filename, std::size_t line_number, const std::string& message)
00151 {
00152   std::cerr << filename << ":" << line_number << ": " << "error: " << message << std::endl;
00153 }
00154 
00155 void
00156 ply_to_ply_converter::magic_callback()
00157 {
00158   (*ostream_) << "ply" << "\n";
00159 }
00160 
00161 void
00162 ply_to_ply_converter::format_callback(pcl::io::ply::format_type format, const std::string& version)
00163 {
00164   input_format_ = format;
00165 
00166   switch (format_) {
00167     case same_format:
00168       output_format_ = input_format_;
00169       break;
00170     case ascii_format:
00171       output_format_ = pcl::io::ply::ascii_format;
00172       break;
00173     case binary_format:
00174       output_format_ = pcl::io::ply::host_byte_order == pcl::io::ply::little_endian_byte_order ? pcl::io::ply::binary_little_endian_format : pcl::io::ply::binary_big_endian_format;
00175       break;
00176     case binary_big_endian_format:
00177       output_format_ = pcl::io::ply::binary_big_endian_format;
00178       break;
00179     case binary_little_endian_format:
00180       output_format_ = pcl::io::ply::binary_little_endian_format;
00181       break;
00182   };
00183 
00184   (*ostream_) << "format ";
00185   switch (output_format_) {
00186     case pcl::io::ply::ascii_format:
00187       (*ostream_) << "ascii";
00188       break;
00189     case pcl::io::ply::binary_little_endian_format:
00190       (*ostream_) << "binary_little_endian";
00191       break;
00192     case pcl::io::ply::binary_big_endian_format:
00193       (*ostream_) << "binary_big_endian";
00194       break;
00195   }
00196   (*ostream_) << " " << version << "\n";
00197 }
00198 
00199 void
00200 ply_to_ply_converter::element_begin_callback()
00201 {
00202   if (output_format_ == pcl::io::ply::ascii_format) {
00203     bol_ = true;
00204   }
00205 }
00206 
00207 void
00208 ply_to_ply_converter::element_end_callback()
00209 {
00210   if (output_format_ == pcl::io::ply::ascii_format) {
00211     (*ostream_) << "\n";
00212   }
00213 }
00214 
00215 boost::tuple<boost::function<void()>, boost::function<void()> > ply_to_ply_converter::element_definition_callback(const std::string& element_name, std::size_t count)
00216 {
00217   (*ostream_) << "element " << element_name << " " << count << "\n";
00218   return boost::tuple<boost::function<void()>, boost::function<void()> >(
00219     boost::bind(&ply_to_ply_converter::element_begin_callback, this),
00220     boost::bind(&ply_to_ply_converter::element_end_callback, this)
00221   );
00222 }
00223 
00224 template <typename ScalarType>
00225 void
00226 ply_to_ply_converter::scalar_property_callback(ScalarType scalar)
00227 {
00228   if (output_format_ == pcl::io::ply::ascii_format) {
00229     using namespace pcl::io::ply::io_operators;
00230     if (bol_) {
00231       bol_ = false;
00232       (*ostream_) << scalar;
00233     }
00234     else {
00235       (*ostream_) << " " << scalar;
00236     }
00237   }
00238   else {
00239     if (((pcl::io::ply::host_byte_order == pcl::io::ply::little_endian_byte_order) && (output_format_ == pcl::io::ply::binary_big_endian_format))
00240       || ((pcl::io::ply::host_byte_order == pcl::io::ply::big_endian_byte_order) && (output_format_ == pcl::io::ply::binary_little_endian_format))) {
00241       pcl::io::ply::swap_byte_order(scalar);
00242     }
00243     ostream_->write(reinterpret_cast<char*>(&scalar), sizeof(scalar));
00244   }
00245 }
00246 
00248 template <typename ScalarType> boost::function<void (ScalarType)> 
00249 ply_to_ply_converter::scalar_property_definition_callback (const std::string&, const std::string& property_name)
00250 {
00251   (*ostream_) << "property " << pcl::io::ply::type_traits<ScalarType>::old_name() << " " << property_name << "\n";
00252   return boost::bind(&ply_to_ply_converter::scalar_property_callback<ScalarType>, this, _1);
00253 }
00254 
00256 template <typename SizeType, typename ScalarType> void
00257 ply_to_ply_converter::list_property_begin_callback (SizeType size)
00258 {
00259   if (output_format_ == pcl::io::ply::ascii_format) 
00260   {
00261     using namespace pcl::io::ply::io_operators;
00262     if (bol_) 
00263     {
00264       bol_ = false;
00265       (*ostream_) << size;
00266     }
00267     else 
00268       (*ostream_) << " " << size;
00269   }
00270   else 
00271   {
00272     if (((pcl::io::ply::host_byte_order == pcl::io::ply::little_endian_byte_order) && (output_format_ == pcl::io::ply::binary_big_endian_format))
00273       || ((pcl::io::ply::host_byte_order == pcl::io::ply::big_endian_byte_order) && (output_format_ == pcl::io::ply::binary_little_endian_format))) {
00274       pcl::io::ply::swap_byte_order(size);
00275     }
00276     ostream_->write(reinterpret_cast<char*>(&size), sizeof(size));
00277   }
00278 }
00279 
00281 template <typename SizeType, typename ScalarType> void
00282 ply_to_ply_converter::list_property_element_callback (ScalarType scalar)
00283 {
00284   if (output_format_ == pcl::io::ply::ascii_format) 
00285   {
00286     using namespace pcl::io::ply::io_operators;
00287     (*ostream_) << " " << scalar;
00288   }
00289   else 
00290   {
00291     if (((pcl::io::ply::host_byte_order == pcl::io::ply::little_endian_byte_order) && (output_format_ == pcl::io::ply::binary_big_endian_format)) || 
00292         ((pcl::io::ply::host_byte_order == pcl::io::ply::big_endian_byte_order) && (output_format_ == pcl::io::ply::binary_little_endian_format)))
00293       pcl::io::ply::swap_byte_order(scalar);
00294 
00295     ostream_->write(reinterpret_cast<char*>(&scalar), sizeof(scalar));
00296   }
00297 }
00298 
00300 template <typename SizeType, typename ScalarType> void
00301 ply_to_ply_converter::list_property_end_callback() {}
00302 
00304 template <typename SizeType, typename ScalarType> boost::tuple<boost::function<void (SizeType)>, 
00305                                                                   boost::function<void (ScalarType)>, 
00306                                                                   boost::function<void ()> > 
00307 ply_to_ply_converter::list_property_definition_callback (const std::string&, const std::string& property_name)
00308 {
00309   (*ostream_) << "property list " << pcl::io::ply::type_traits<SizeType>::old_name() << " " << pcl::io::ply::type_traits<ScalarType>::old_name() << " " << property_name << "\n";
00310   return boost::tuple<boost::function<void (SizeType)>, boost::function<void (ScalarType)>, boost::function<void ()> >(
00311     boost::bind(&ply_to_ply_converter::list_property_begin_callback<SizeType, ScalarType>, this, _1),
00312     boost::bind(&ply_to_ply_converter::list_property_element_callback<SizeType, ScalarType>, this, _1),
00313     boost::bind(&ply_to_ply_converter::list_property_end_callback<SizeType, ScalarType>, this)
00314   );
00315 }
00316 
00318 void
00319 ply_to_ply_converter::comment_callback(const std::string& comment)
00320 {
00321   (*ostream_) << comment << "\n";
00322 }
00323 
00325 void
00326 ply_to_ply_converter::obj_info_callback(const std::string& obj_info)
00327 {
00328   (*ostream_) << obj_info << "\n";
00329 }
00330 
00332 bool 
00333 ply_to_ply_converter::end_header_callback()
00334 {
00335   (*ostream_) << "end_header" << "\n";
00336   return true;
00337 }
00338 
00340 bool 
00341 ply_to_ply_converter::convert (std::istream&, std::ostream& ostream)
00342 {
00343   pcl::io::ply::ply_parser::flags_type ply_parser_flags = 0;
00344 
00345   pcl::io::ply::ply_parser ply_parser(ply_parser_flags);
00346 
00347   std::string ifilename;
00348 
00349   ply_parser.info_callback(boost::bind(&ply_to_ply_converter::info_callback, this, boost::ref(ifilename), _1, _2));
00350   ply_parser.warning_callback(boost::bind(&ply_to_ply_converter::warning_callback, this, boost::ref(ifilename), _1, _2));
00351   ply_parser.error_callback(boost::bind(&ply_to_ply_converter::error_callback, this, boost::ref(ifilename), _1, _2));
00352 
00353   ply_parser.magic_callback(boost::bind(&ply_to_ply_converter::magic_callback, this));
00354   ply_parser.format_callback(boost::bind(&ply_to_ply_converter::format_callback, this, _1, _2));
00355   ply_parser.element_definition_callback(boost::bind(&ply_to_ply_converter::element_definition_callback, this, _1, _2));
00356 
00357   pcl::io::ply::ply_parser::scalar_property_definition_callbacks_type scalar_property_definition_callbacks;
00358 
00359   pcl::io::ply::at<pcl::io::ply::int8>(scalar_property_definition_callbacks) = boost::bind(&ply_to_ply_converter::scalar_property_definition_callback<pcl::io::ply::int8>, this, _1, _2);
00360   pcl::io::ply::at<pcl::io::ply::int16>(scalar_property_definition_callbacks) = boost::bind(&ply_to_ply_converter::scalar_property_definition_callback<pcl::io::ply::int16>, this, _1, _2);
00361   pcl::io::ply::at<pcl::io::ply::int32>(scalar_property_definition_callbacks) = boost::bind(&ply_to_ply_converter::scalar_property_definition_callback<pcl::io::ply::int32>, this, _1, _2);
00362   pcl::io::ply::at<pcl::io::ply::uint8>(scalar_property_definition_callbacks) = boost::bind(&ply_to_ply_converter::scalar_property_definition_callback<pcl::io::ply::uint8>, this, _1, _2);
00363   pcl::io::ply::at<pcl::io::ply::uint16>(scalar_property_definition_callbacks) = boost::bind(&ply_to_ply_converter::scalar_property_definition_callback<pcl::io::ply::uint16>, this, _1, _2);
00364   pcl::io::ply::at<pcl::io::ply::uint32>(scalar_property_definition_callbacks) = boost::bind(&ply_to_ply_converter::scalar_property_definition_callback<pcl::io::ply::uint32>, this, _1, _2);
00365   pcl::io::ply::at<pcl::io::ply::float32>(scalar_property_definition_callbacks) = boost::bind(&ply_to_ply_converter::scalar_property_definition_callback<pcl::io::ply::float32>, this, _1, _2);
00366   pcl::io::ply::at<pcl::io::ply::float64>(scalar_property_definition_callbacks) = boost::bind(&ply_to_ply_converter::scalar_property_definition_callback<pcl::io::ply::float64>, this, _1, _2);
00367 
00368   ply_parser.scalar_property_definition_callbacks(scalar_property_definition_callbacks);
00369 
00370   pcl::io::ply::ply_parser::list_property_definition_callbacks_type list_property_definition_callbacks;
00371 
00372   pcl::io::ply::at<pcl::io::ply::uint8, pcl::io::ply::int8>(list_property_definition_callbacks) = boost::bind(&ply_to_ply_converter::list_property_definition_callback<pcl::io::ply::uint8, pcl::io::ply::int8>, this, _1, _2);
00373   pcl::io::ply::at<pcl::io::ply::uint8, pcl::io::ply::int16>(list_property_definition_callbacks) = boost::bind(&ply_to_ply_converter::list_property_definition_callback<pcl::io::ply::uint8, pcl::io::ply::int16>, this, _1, _2);
00374   pcl::io::ply::at<pcl::io::ply::uint8, pcl::io::ply::int32>(list_property_definition_callbacks) = boost::bind(&ply_to_ply_converter::list_property_definition_callback<pcl::io::ply::uint8, pcl::io::ply::int32>, this, _1, _2);
00375   pcl::io::ply::at<pcl::io::ply::uint8, pcl::io::ply::uint8>(list_property_definition_callbacks) = boost::bind(&ply_to_ply_converter::list_property_definition_callback<pcl::io::ply::uint8, pcl::io::ply::uint8>, this, _1, _2);
00376   pcl::io::ply::at<pcl::io::ply::uint8, pcl::io::ply::uint16>(list_property_definition_callbacks) = boost::bind(&ply_to_ply_converter::list_property_definition_callback<pcl::io::ply::uint8, pcl::io::ply::uint16>, this, _1, _2);
00377   pcl::io::ply::at<pcl::io::ply::uint8, pcl::io::ply::uint32>(list_property_definition_callbacks) = boost::bind(&ply_to_ply_converter::list_property_definition_callback<pcl::io::ply::uint8, pcl::io::ply::uint32>, this, _1, _2);
00378   pcl::io::ply::at<pcl::io::ply::uint8, pcl::io::ply::float32>(list_property_definition_callbacks) = boost::bind(&ply_to_ply_converter::list_property_definition_callback<pcl::io::ply::uint8, pcl::io::ply::float32>, this, _1, _2);
00379   pcl::io::ply::at<pcl::io::ply::uint8, pcl::io::ply::float64>(list_property_definition_callbacks) = boost::bind(&ply_to_ply_converter::list_property_definition_callback<pcl::io::ply::uint8, pcl::io::ply::float64>, this, _1, _2);
00380 
00381   pcl::io::ply::at<pcl::io::ply::uint16, pcl::io::ply::int8>(list_property_definition_callbacks) = boost::bind(&ply_to_ply_converter::list_property_definition_callback<pcl::io::ply::uint16, pcl::io::ply::int8>, this, _1, _2);
00382   pcl::io::ply::at<pcl::io::ply::uint16, pcl::io::ply::int16>(list_property_definition_callbacks) = boost::bind(&ply_to_ply_converter::list_property_definition_callback<pcl::io::ply::uint16, pcl::io::ply::int16>, this, _1, _2);
00383   pcl::io::ply::at<pcl::io::ply::uint16, pcl::io::ply::int32>(list_property_definition_callbacks) = boost::bind(&ply_to_ply_converter::list_property_definition_callback<pcl::io::ply::uint16, pcl::io::ply::int32>, this, _1, _2);
00384   pcl::io::ply::at<pcl::io::ply::uint16, pcl::io::ply::uint8>(list_property_definition_callbacks) = boost::bind(&ply_to_ply_converter::list_property_definition_callback<pcl::io::ply::uint16, pcl::io::ply::uint8>, this, _1, _2);
00385   pcl::io::ply::at<pcl::io::ply::uint16, pcl::io::ply::uint16>(list_property_definition_callbacks) = boost::bind(&ply_to_ply_converter::list_property_definition_callback<pcl::io::ply::uint16, pcl::io::ply::uint16>, this, _1, _2);
00386   pcl::io::ply::at<pcl::io::ply::uint16, pcl::io::ply::uint32>(list_property_definition_callbacks) = boost::bind(&ply_to_ply_converter::list_property_definition_callback<pcl::io::ply::uint16, pcl::io::ply::uint32>, this, _1, _2);
00387   pcl::io::ply::at<pcl::io::ply::uint16, pcl::io::ply::float32>(list_property_definition_callbacks) = boost::bind(&ply_to_ply_converter::list_property_definition_callback<pcl::io::ply::uint16, pcl::io::ply::float32>, this, _1, _2);
00388   pcl::io::ply::at<pcl::io::ply::uint16, pcl::io::ply::float64>(list_property_definition_callbacks) = boost::bind(&ply_to_ply_converter::list_property_definition_callback<pcl::io::ply::uint16, pcl::io::ply::float64>, this, _1, _2);
00389 
00390   pcl::io::ply::at<pcl::io::ply::uint32, pcl::io::ply::int8>(list_property_definition_callbacks) = boost::bind(&ply_to_ply_converter::list_property_definition_callback<pcl::io::ply::uint32, pcl::io::ply::int8>, this, _1, _2);
00391   pcl::io::ply::at<pcl::io::ply::uint32, pcl::io::ply::int16>(list_property_definition_callbacks) = boost::bind(&ply_to_ply_converter::list_property_definition_callback<pcl::io::ply::uint32, pcl::io::ply::int16>, this, _1, _2);
00392   pcl::io::ply::at<pcl::io::ply::uint32, pcl::io::ply::int32>(list_property_definition_callbacks) = boost::bind(&ply_to_ply_converter::list_property_definition_callback<pcl::io::ply::uint32, pcl::io::ply::int32>, this, _1, _2);
00393   pcl::io::ply::at<pcl::io::ply::uint32, pcl::io::ply::uint8>(list_property_definition_callbacks) = boost::bind(&ply_to_ply_converter::list_property_definition_callback<pcl::io::ply::uint32, pcl::io::ply::uint8>, this, _1, _2);
00394   pcl::io::ply::at<pcl::io::ply::uint32, pcl::io::ply::uint16>(list_property_definition_callbacks) = boost::bind(&ply_to_ply_converter::list_property_definition_callback<pcl::io::ply::uint32, pcl::io::ply::uint16>, this, _1, _2);
00395   pcl::io::ply::at<pcl::io::ply::uint32, pcl::io::ply::uint32>(list_property_definition_callbacks) = boost::bind(&ply_to_ply_converter::list_property_definition_callback<pcl::io::ply::uint32, pcl::io::ply::uint32>, this, _1, _2);
00396   pcl::io::ply::at<pcl::io::ply::uint32, pcl::io::ply::float32>(list_property_definition_callbacks) = boost::bind(&ply_to_ply_converter::list_property_definition_callback<pcl::io::ply::uint32, pcl::io::ply::float32>, this, _1, _2);
00397   pcl::io::ply::at<pcl::io::ply::uint32, pcl::io::ply::float64>(list_property_definition_callbacks) = boost::bind(&ply_to_ply_converter::list_property_definition_callback<pcl::io::ply::uint32, pcl::io::ply::float64>, this, _1, _2);
00398 
00399   ply_parser.list_property_definition_callbacks(list_property_definition_callbacks);
00400 
00401   ply_parser.comment_callback(boost::bind(&ply_to_ply_converter::comment_callback, this, _1));
00402   ply_parser.obj_info_callback(boost::bind(&ply_to_ply_converter::obj_info_callback, this, _1));
00403   ply_parser.end_header_callback(boost::bind(&ply_to_ply_converter::end_header_callback, this));
00404 
00405   ostream_ = &ostream;
00406   return ply_parser.parse(ifilename);
00407 }
00408 
00410 int 
00411 main(int argc, char* argv[])
00412 {
00413   ply_to_ply_converter::format_type ply_to_ply_converter_format = ply_to_ply_converter::same_format;
00414 
00415   int argi;
00416   for (argi = 1; argi < argc; ++argi) {
00417 
00418     if (argv[argi][0] != '-') {
00419       break;
00420     }
00421     if (argv[argi][1] == 0) {
00422       ++argi;
00423       break;
00424     }
00425     char short_opt, *long_opt, *opt_arg;
00426     if (argv[argi][1] != '-') {
00427       short_opt = argv[argi][1];
00428       opt_arg = &argv[argi][2];
00429       long_opt = &argv[argi][2];
00430       while (*long_opt != '\0') {
00431         ++long_opt;
00432       }
00433     }
00434     else {
00435       short_opt = 0;
00436       long_opt = &argv[argi][2];
00437       opt_arg = long_opt;
00438       while ((*opt_arg != '=') && (*opt_arg != '\0')) {
00439         ++opt_arg;
00440       }
00441       if (*opt_arg == '=') {
00442         *opt_arg++ = '\0';
00443       }
00444     }
00445 
00446     if ((short_opt == 'h') || (std::strcmp(long_opt, "help") == 0)) {
00447       std::cout << "Usage: ply2ply [OPTION] [[INFILE] OUTFILE]\n";
00448       std::cout << "Parse an PLY file.\n";
00449       std::cout << "\n";
00450       std::cout << "  -h, --help           display this help and exit\n";
00451       std::cout << "  -v, --version        output version information and exit\n";
00452       std::cout << "  -f, --format=FORMAT  set format\n";
00453       std::cout << "\n";
00454       std::cout << "FORMAT may be one of the following: ascii, binary, binary_big_endian,\n";
00455       std::cout << "binary_little_endian.\n";
00456       std::cout << "If no format is given, the format of INFILE is kept.\n";
00457       std::cout << "\n";
00458       std::cout << "With no INFILE/OUTFILE, or when INFILE/OUTFILE is -, read standard input/output.\n";
00459       std::cout << "\n";
00460       std::cout << "Report bugs to <www.pointclouds.org/issues>.\n";
00461       return EXIT_SUCCESS;
00462     }
00463 
00464     else if ((short_opt == 'v') || (std::strcmp(long_opt, "version") == 0)) {
00465       std::cout << "ply2ply\n";
00466       std::cout << " Point Cloud Library (PCL) - www.pointclouds.org\n";
00467       std::cout << " Copyright (c) 2007-2012, Ares Lagae\n";
00468       std::cout << " Copyright (c) 2012, Willow Garage, Inc.\n";
00469       std::cout << " All rights reserved.\n";
00470       std::cout << " Redistribution and use in source and binary forms, with or without\n";
00471       std::cout << " modification, are permitted provided that the following conditions\n";
00472       std::cout << " are met:\n";
00473       std::cout << "  * Redistributions of source code must retain the above copyright\n";
00474       std::cout << "    notice, this list of conditions and the following disclaimer.\n";
00475       std::cout << "  * Redistributions in binary form must reproduce the above\n";
00476       std::cout << "    copyright notice, this list of conditions and the following\n";
00477       std::cout << "    disclaimer in the documentation and/or other materials provided\n";
00478       std::cout << "    with the distribution.\n";
00479       std::cout << "  * Neither the name of Willow Garage, Inc. nor the names of its\n";
00480       std::cout << "    contributors may be used to endorse or promote products derived\n";
00481       std::cout << "    from this software without specific prior written permission.\n";
00482       std::cout << " THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS\n";
00483       std::cout << " \"AS IS\" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT\n";
00484       std::cout << " LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS\n";
00485       std::cout << " FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE\n";
00486       std::cout << " COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,\n";
00487       std::cout << " INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,\n";
00488       std::cout << " BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;\n";
00489       std::cout << " LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER\n";
00490       std::cout << " CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT\n";
00491       std::cout << " LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN\n";
00492       std::cout << " ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE\n";
00493       std::cout << " POSSIBILITY OF SUCH DAMAGE.\n";
00494       return EXIT_SUCCESS;
00495     }
00496 
00497     else if ((short_opt == 'f') || (std::strcmp(long_opt, "format") == 0)) {
00498       if (strcmp(opt_arg, "ascii") == 0) {
00499         ply_to_ply_converter_format = ply_to_ply_converter::ascii_format;
00500       }
00501       else if (strcmp(opt_arg, "binary") == 0) {
00502         ply_to_ply_converter_format = ply_to_ply_converter::binary_format;
00503       }
00504       else if (strcmp(opt_arg, "binary_little_endian") == 0) {
00505         ply_to_ply_converter_format = ply_to_ply_converter::binary_little_endian_format;
00506       }
00507       else if (strcmp(opt_arg, "binary_big_endian") == 0) {
00508         ply_to_ply_converter_format = ply_to_ply_converter::binary_big_endian_format;
00509       }
00510       else {
00511         std::cerr << "ply2ply: " << "invalid option `" << argv[argi] << "'" << "\n";
00512         std::cerr << "Try `" << argv[0] << " --help' for more information.\n";
00513         return EXIT_FAILURE;
00514       }
00515     }
00516 
00517     else {
00518       std::cerr << "ply2ply: " << "invalid option `" << argv[argi] << "'" << "\n";
00519       std::cerr << "Try `" << argv[0] << " --help' for more information.\n";
00520       return EXIT_FAILURE;
00521     }
00522   }
00523 
00524   int parc = argc - argi;
00525   char** parv = argv + argi;
00526   if (parc > 2) {
00527     std::cerr << "ply2ply: " << "too many parameters" << "\n";
00528     std::cerr << "Try `" << argv[0] << " --help' for more information.\n";
00529     return EXIT_FAILURE;
00530   }
00531 
00532   std::ifstream ifstream;
00533   const char* ifilename = "";
00534   if (parc > 0) {
00535     ifilename = parv[0];
00536     if (std::strcmp(ifilename, "-") != 0) {
00537       ifstream.open(ifilename);
00538       if (!ifstream.is_open()) {
00539         std::cerr << "ply2ply: " << ifilename << ": " << "no such file or directory" << "\n";
00540         return EXIT_FAILURE;
00541       }
00542     }
00543   }
00544 
00545   std::ofstream ofstream;
00546   const char* ofilename = "";
00547   if (parc > 1) {
00548     ofilename = parv[1];
00549     if (std::strcmp(ofilename, "-") != 0) {
00550       ofstream.open(ofilename);
00551       if (!ofstream.is_open()) {
00552         std::cerr << "ply2ply: " << ofilename << ": " << "could not open file" << "\n";
00553         return EXIT_FAILURE;
00554       }
00555     }
00556   }
00557 
00558   std::istream& istream = ifstream.is_open() ? ifstream : std::cin;
00559   std::ostream& ostream = ofstream.is_open() ? ofstream : std::cout;
00560 
00561   class ply_to_ply_converter ply_to_ply_converter(ply_to_ply_converter_format);
00562   return ply_to_ply_converter.convert(istream, ostream);
00563 }


pcl
Author(s): Open Perception
autogenerated on Mon Oct 6 2014 03:16:32