ply2raw.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$
00037  *
00038  */
00039 
00040 #include <cstdlib>
00041 #include <cstring>
00042 #include <fstream>
00043 #include <iostream>
00044 
00045 #include <pcl/io/boost.h>
00046 #include <pcl/io/ply/ply_parser.h>
00047 
00061 class ply_to_raw_converter
00062 {
00063   public:
00064     ply_to_raw_converter () : 
00065       ostream_ (), vertex_x_ (0), vertex_y_ (0), vertex_z_ (0), 
00066       face_vertex_indices_element_index_ (),
00067       face_vertex_indices_first_element_ (), 
00068       face_vertex_indices_previous_element_ (),
00069       vertices_ ()
00070     {}
00071 
00072     ply_to_raw_converter (const ply_to_raw_converter &f) :
00073       ostream_ (), vertex_x_ (0), vertex_y_ (0), vertex_z_ (0), 
00074       face_vertex_indices_element_index_ (),
00075       face_vertex_indices_first_element_ (), 
00076       face_vertex_indices_previous_element_ (),
00077       vertices_ ()
00078     {
00079       *this = f;
00080     }
00081 
00082     ply_to_raw_converter&
00083     operator = (const ply_to_raw_converter &f)
00084     {
00085       ostream_ = f.ostream_;
00086       vertex_x_ = f.vertex_x_;
00087       vertex_y_ = f.vertex_y_;
00088       vertex_z_ = f.vertex_z_;
00089       face_vertex_indices_element_index_ = f.face_vertex_indices_element_index_;
00090       face_vertex_indices_first_element_ = f.face_vertex_indices_first_element_;
00091       face_vertex_indices_previous_element_ = f.face_vertex_indices_previous_element_;
00092       return (*this);
00093     }
00094 
00095     bool 
00096     convert (std::istream& istream, const std::string& istream_filename, std::ostream& ostream, const std::string& ostream_filename);
00097 
00098   private:
00099     void
00100     info_callback (const std::string& filename, std::size_t line_number, const std::string& message);
00101 
00102     void
00103     warning_callback (const std::string& filename, std::size_t line_number, const std::string& message);
00104 
00105     void
00106     error_callback (const std::string& filename, std::size_t line_number, const std::string& message);
00107 
00108     boost::tuple<boost::function<void ()>, boost::function<void ()> > 
00109     element_definition_callback (const std::string& element_name, std::size_t count);
00110 
00111     template <typename ScalarType> boost::function<void (ScalarType)> 
00112     scalar_property_definition_callback (const std::string& element_name, const std::string& property_name);
00113 
00114     template <typename SizeType, typename ScalarType>  boost::tuple<boost::function<void (SizeType)>, 
00115                                                                        boost::function<void (ScalarType)>, 
00116                                                                        boost::function<void ()> > 
00117     list_property_definition_callback (const std::string& element_name, const std::string& property_name);
00118 
00119     void
00120     vertex_begin ();
00121 
00122     void
00123     vertex_x (pcl::io::ply::float32 x);
00124 
00125     void
00126     vertex_y (pcl::io::ply::float32 y);
00127 
00128     void
00129     vertex_z (pcl::io::ply::float32 z);
00130 
00131     void
00132     vertex_end ();
00133 
00134     void
00135     face_begin ();
00136 
00137     void
00138     face_vertex_indices_begin (pcl::io::ply::uint8 size);
00139 
00140     void
00141     face_vertex_indices_element (pcl::io::ply::int32 vertex_index);
00142 
00143     void
00144     face_vertex_indices_end ();
00145 
00146     void
00147     face_end ();
00148 
00149     std::ostream* ostream_;
00150     pcl::io::ply::float32 vertex_x_, vertex_y_, vertex_z_;
00151     pcl::io::ply::int32 face_vertex_indices_element_index_, face_vertex_indices_first_element_, face_vertex_indices_previous_element_;
00152     std::vector<boost::tuple<pcl::io::ply::float32, pcl::io::ply::float32, pcl::io::ply::float32> > vertices_;
00153 };
00154 
00155 void
00156 ply_to_raw_converter::info_callback (const std::string& filename, std::size_t line_number, const std::string& message)
00157 {
00158   std::cerr << filename << ":" << line_number << ": " << "info: " << message << std::endl;
00159 }
00160 
00161 void
00162 ply_to_raw_converter::warning_callback (const std::string& filename, std::size_t line_number, const std::string& message)
00163 {
00164   std::cerr << filename << ":" << line_number << ": " << "warning: " << message << std::endl;
00165 }
00166 
00167 void
00168 ply_to_raw_converter::error_callback (const std::string& filename, std::size_t line_number, const std::string& message)
00169 {
00170   std::cerr << filename << ":" << line_number << ": " << "error: " << message << std::endl;
00171 }
00172 
00173 boost::tuple<boost::function<void ()>, boost::function<void ()> > 
00174 ply_to_raw_converter::element_definition_callback (const std::string& element_name, std::size_t)
00175 {
00176   if (element_name == "vertex") {
00177     return boost::tuple<boost::function<void ()>, boost::function<void ()> > (
00178       boost::bind (&ply_to_raw_converter::vertex_begin, this),
00179       boost::bind (&ply_to_raw_converter::vertex_end, this)
00180     );
00181   }
00182   else if (element_name == "face") {
00183     return boost::tuple<boost::function<void ()>, boost::function<void ()> > (
00184       boost::bind (&ply_to_raw_converter::face_begin, this),
00185       boost::bind (&ply_to_raw_converter::face_end, this)
00186     );
00187   }
00188   else {
00189     return boost::tuple<boost::function<void ()>, boost::function<void ()> > (0, 0);
00190   }
00191 }
00192 
00193 template <> boost::function<void (pcl::io::ply::float32)> 
00194 ply_to_raw_converter::scalar_property_definition_callback (const std::string& element_name, const std::string& property_name)
00195 {
00196   if (element_name == "vertex") {
00197     if (property_name == "x") {
00198       return boost::bind (&ply_to_raw_converter::vertex_x, this, _1);
00199     }
00200     else if (property_name == "y") {
00201       return boost::bind (&ply_to_raw_converter::vertex_y, this, _1);
00202     }
00203     else if (property_name == "z") {
00204       return boost::bind (&ply_to_raw_converter::vertex_z, this, _1);
00205     }
00206     else {
00207       return 0;
00208     }
00209   }
00210   else {
00211     return 0;
00212   }
00213 }
00214 
00215 template <> boost::tuple<boost::function<void (pcl::io::ply::uint8)>, 
00216                             boost::function<void (pcl::io::ply::int32)>, 
00217                             boost::function<void ()> > 
00218 ply_to_raw_converter::list_property_definition_callback (const std::string& element_name, const std::string& property_name)
00219 {
00220   if ((element_name == "face") && (property_name == "vertex_indices")) 
00221   {
00222     return boost::tuple<boost::function<void (pcl::io::ply::uint8)>, 
00223       boost::function<void (pcl::io::ply::int32)>, 
00224       boost::function<void ()> > (
00225         boost::bind (&ply_to_raw_converter::face_vertex_indices_begin, this, _1),
00226       boost::bind (&ply_to_raw_converter::face_vertex_indices_element, this, _1),
00227       boost::bind (&ply_to_raw_converter::face_vertex_indices_end, this)
00228     );
00229   }
00230   else {
00231     return boost::tuple<boost::function<void (pcl::io::ply::uint8)>, 
00232       boost::function<void (pcl::io::ply::int32)>, 
00233       boost::function<void ()> > (0, 0, 0);
00234   }
00235 }
00236 
00237 void
00238 ply_to_raw_converter::vertex_begin () {}
00239 
00240 void
00241 ply_to_raw_converter::vertex_x (pcl::io::ply::float32 x)
00242 {
00243   vertex_x_ = x;
00244 }
00245 
00246 void
00247 ply_to_raw_converter::vertex_y (pcl::io::ply::float32 y)
00248 {
00249   vertex_y_ = y;
00250 }
00251 
00252 void
00253 ply_to_raw_converter::vertex_z (pcl::io::ply::float32 z)
00254 {
00255   vertex_z_ = z;
00256 }
00257 
00258 void
00259 ply_to_raw_converter::vertex_end ()
00260 {
00261   vertices_.push_back (boost::tuple<pcl::io::ply::float32, pcl::io::ply::float32, pcl::io::ply::float32 > (vertex_x_, vertex_y_, vertex_z_));
00262 }
00263 
00264 void
00265 ply_to_raw_converter::face_begin () {}
00266 
00267 void
00268 ply_to_raw_converter::face_vertex_indices_begin (pcl::io::ply::uint8)
00269 {
00270   face_vertex_indices_element_index_ = 0;
00271 }
00272 
00273 void
00274 ply_to_raw_converter::face_vertex_indices_element (pcl::io::ply::int32 vertex_index)
00275 {
00276   if (face_vertex_indices_element_index_ == 0) {
00277     face_vertex_indices_first_element_ = vertex_index;
00278   }
00279   else if (face_vertex_indices_element_index_ == 1) {
00280     face_vertex_indices_previous_element_ = vertex_index;
00281   }
00282   else {
00283     (*ostream_) << boost::get<0> (vertices_[   face_vertex_indices_first_element_])
00284          << " " << boost::get<1> (vertices_[   face_vertex_indices_first_element_])
00285          << " " << boost::get<2> (vertices_[   face_vertex_indices_first_element_])
00286          << " " << boost::get<0> (vertices_[face_vertex_indices_previous_element_])
00287          << " " << boost::get<1> (vertices_[face_vertex_indices_previous_element_])
00288          << " " << boost::get<2> (vertices_[face_vertex_indices_previous_element_])
00289          << " " << boost::get<0> (vertices_[                         vertex_index])
00290          << " " << boost::get<1> (vertices_[                         vertex_index])
00291          << " " << boost::get<2> (vertices_[                         vertex_index]) << "\n";
00292     face_vertex_indices_previous_element_ = vertex_index;
00293   }
00294   ++face_vertex_indices_element_index_;
00295 }
00296 
00297 void
00298 ply_to_raw_converter::face_vertex_indices_end () {}
00299 
00300 void
00301 ply_to_raw_converter::face_end () {}
00302 
00303 bool 
00304 ply_to_raw_converter::convert (std::istream&, const std::string& istream_filename, std::ostream& ostream, const std::string&)
00305 {
00306   pcl::io::ply::ply_parser::flags_type ply_parser_flags = 0;
00307   pcl::io::ply::ply_parser ply_parser (ply_parser_flags);
00308 
00309   ply_parser.info_callback (boost::bind (&ply_to_raw_converter::info_callback, this, boost::ref (istream_filename), _1, _2));
00310   ply_parser.warning_callback (boost::bind (&ply_to_raw_converter::warning_callback, this, boost::ref (istream_filename), _1, _2));
00311   ply_parser.error_callback (boost::bind (&ply_to_raw_converter::error_callback, this, boost::ref (istream_filename), _1, _2)); 
00312 
00313   ply_parser.element_definition_callback (boost::bind (&ply_to_raw_converter::element_definition_callback, this, _1, _2));
00314 
00315   pcl::io::ply::ply_parser::scalar_property_definition_callbacks_type scalar_property_definition_callbacks;
00316   pcl::io::ply::at<pcl::io::ply::float32> (scalar_property_definition_callbacks) = boost::bind (&ply_to_raw_converter::scalar_property_definition_callback<pcl::io::ply::float32>, this, _1, _2);
00317   ply_parser.scalar_property_definition_callbacks (scalar_property_definition_callbacks);
00318 
00319   pcl::io::ply::ply_parser::list_property_definition_callbacks_type list_property_definition_callbacks;
00320   pcl::io::ply::at<pcl::io::ply::uint8, pcl::io::ply::int32> (list_property_definition_callbacks) = boost::bind (&ply_to_raw_converter::list_property_definition_callback<pcl::io::ply::uint8, pcl::io::ply::int32>, this, _1, _2);
00321   ply_parser.list_property_definition_callbacks (list_property_definition_callbacks);
00322 
00323   ostream_ = &ostream;
00324 
00325   return ply_parser.parse (istream_filename);
00326 }
00327 
00328 int main (int argc, char* argv[])
00329 {
00330   int argi;
00331   for (argi = 1; argi < argc; ++argi) {
00332 
00333     if (argv[argi][0] != '-') {
00334       break;
00335     }
00336     if (argv[argi][1] == 0) {
00337       ++argi;
00338       break;
00339     }
00340     char short_opt, *long_opt, *opt_arg;
00341     if (argv[argi][1] != '-') {
00342       short_opt = argv[argi][1];
00343       opt_arg = &argv[argi][2];
00344       long_opt = &argv[argi][2];
00345       while (*long_opt != '\0') {
00346         ++long_opt;
00347       }
00348     }
00349     else {
00350       short_opt = 0;
00351       long_opt = &argv[argi][2];
00352       opt_arg = long_opt;
00353       while ((*opt_arg != '=') && (*opt_arg != '\0')) {
00354         ++opt_arg;
00355       }
00356       if (*opt_arg == '=') {
00357         *opt_arg++ = '\0';
00358       }
00359     }
00360 
00361     if ((short_opt == 'h') || (std::strcmp (long_opt, "help") == 0)) {
00362       std::cout << "Usage: ply2raw [OPTION] [[INFILE] OUTFILE]\n";
00363       std::cout << "Convert from PLY to POV-Ray RAW triangle format.\n";
00364       std::cout << "\n";
00365       std::cout << "  -h, --help       display this help and exit\n";
00366       std::cout << "  -v, --version    output version information and exit\n";
00367       std::cout << "\n";
00368       std::cout << "With no INFILE/OUTFILE, or when INFILE/OUTFILE is -, read standard input/output.\n";
00369       std::cout << "\n";
00370       std::cout << "The following PLY elements and properties are supported.\n";
00371       std::cout << "  element vertex\n";
00372       std::cout << "    property float32 x\n";
00373       std::cout << "    property float32 y\n";
00374       std::cout << "    property float32 z\n";
00375       std::cout << "  element face\n";
00376       std::cout << "    property list uint8 int32 vertex_indices.\n";
00377       std::cout << "\n";
00378       std::cout << "Report bugs to <www.pointclouds.org/issues>.\n";
00379       return EXIT_SUCCESS;
00380     }
00381 
00382     else if ((short_opt == 'v') || (std::strcmp (long_opt, "version") == 0)) {
00383       std::cout << "ply2raw \n";
00384       std::cout << " Point Cloud Library (PCL) - www.pointclouds.org\n";
00385       std::cout << " Copyright (c) 2007-2012, Ares Lagae\n";
00386       std::cout << " Copyright (c) 2012, Willow Garage, Inc.\n";
00387       std::cout << " All rights reserved.\n";
00388       std::cout << " Redistribution and use in source and binary forms, with or without\n";
00389       std::cout << " modification, are permitted provided that the following conditions\n";
00390       std::cout << " are met:\n";
00391       std::cout << "  * Redistributions of source code must retain the above copyright\n";
00392       std::cout << "    notice, this list of conditions and the following disclaimer.\n";
00393       std::cout << "  * Redistributions in binary form must reproduce the above\n";
00394       std::cout << "    copyright notice, this list of conditions and the following\n";
00395       std::cout << "    disclaimer in the documentation and/or other materials provided\n";
00396       std::cout << "    with the distribution.\n";
00397       std::cout << "  * Neither the name of Willow Garage, Inc. nor the names of its\n";
00398       std::cout << "    contributors may be used to endorse or promote products derived\n";
00399       std::cout << "    from this software without specific prior written permission.\n";
00400       std::cout << " THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS\n";
00401       std::cout << " \"AS IS\" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT\n";
00402       std::cout << " LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS\n";
00403       std::cout << " FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE\n";
00404       std::cout << " COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,\n";
00405       std::cout << " INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,\n";
00406       std::cout << " BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;\n";
00407       std::cout << " LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER\n";
00408       std::cout << " CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT\n";
00409       std::cout << " LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN\n";
00410       std::cout << " ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE\n";
00411       std::cout << " POSSIBILITY OF SUCH DAMAGE.\n";
00412       return EXIT_SUCCESS;
00413     }
00414 
00415     else {
00416       std::cerr << "ply2raw: " << "invalid option `" << argv[argi] << "'" << "\n";
00417       std::cerr << "Try `" << argv[0] << " --help' for more information.\n";
00418       return EXIT_FAILURE;
00419     }
00420   }
00421 
00422   int parc = argc - argi;
00423   char** parv = argv + argi;
00424   if (parc > 2) {
00425     std::cerr << "ply2raw: " << "too many parameters" << "\n";
00426     std::cerr << "Try `" << argv[0] << " --help' for more information.\n";
00427     return EXIT_FAILURE;
00428   }
00429 
00430   std::ifstream ifstream;
00431   const char* istream_filename = "";
00432   if (parc > 0) {
00433     istream_filename = parv[0];
00434     if (std::strcmp (istream_filename, "-") != 0) {
00435       ifstream.open (istream_filename);
00436       if (!ifstream.is_open ()) {
00437         std::cerr << "ply2raw: " << istream_filename << ": " << "no such file or directory" << "\n";
00438         return EXIT_FAILURE;
00439       }
00440     }
00441   }
00442 
00443   std::ofstream ofstream;
00444   const char* ostream_filename = "";
00445   if (parc > 1) {
00446     ostream_filename = parv[1];
00447     if (std::strcmp (ostream_filename, "-") != 0) {
00448       ofstream.open (ostream_filename);
00449       if (!ofstream.is_open ()) {
00450         std::cerr << "ply2raw: " << ostream_filename << ": " << "could not open file" << "\n";
00451         return EXIT_FAILURE;
00452       }
00453     }
00454   }
00455 
00456   std::istream& istream = ifstream.is_open () ? ifstream : std::cin;
00457   std::ostream& ostream = ofstream.is_open () ? ofstream : std::cout;
00458 
00459   class ply_to_raw_converter ply_to_raw_converter;
00460   return ply_to_raw_converter.convert (istream, istream_filename, ostream, ostream_filename);
00461 }


pcl
Author(s): Open Perception
autogenerated on Wed Aug 26 2015 15:28:18