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


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