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


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