ply_parser.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 <pcl/io/ply/ply_parser.h>
00042 
00043 bool pcl::io::ply::ply_parser::parse (const std::string& filename)
00044 {
00045   std::ifstream istream (filename.c_str (), std::ios::in | std::ios::binary);
00046 
00047   std::string line;
00048   line_number_ = 0;
00049 
00050   std::size_t number_of_format_statements = 0; 
00051   std::size_t number_of_element_statements = 0; 
00052   std::size_t number_of_property_statements = 0; 
00053   std::size_t number_of_obj_info_statements = 0; 
00054   std::size_t number_of_comment_statements = 0;
00055 
00056   format_type format = pcl::io::ply::unknown;
00057   std::vector< boost::shared_ptr<element> > elements;
00058 
00059   // magic
00060   char magic[4];
00061   istream.read (magic, 4);
00062   if (magic[3] == '\r') // Check if CR/LF
00063     istream.ignore (1);
00064   ++line_number_;
00065   if (!istream)
00066   {
00067     if (error_callback_)
00068       error_callback_ (line_number_, "parse error");
00069     return false;
00070   }
00071 
00072   if ((magic[0] != 'p') || (magic[1] != 'l') || (magic[2] != 'y'))
00073   {
00074     if (error_callback_)
00075       error_callback_ (line_number_, "parse error");
00076     return false;
00077   }
00078 
00079   if (magic_callback_)
00080     magic_callback_ ();
00081 
00082   while (std::getline (istream, line))
00083   {
00084     ++line_number_;
00085     std::istringstream stringstream (line);
00086     stringstream.unsetf (std::ios_base::skipws);
00087 
00088     stringstream >> std::ws;
00089     if (stringstream.eof ())
00090     {
00091       if (warning_callback_)
00092         warning_callback_ (line_number_, "ignoring line '" + line + "'");
00093     }
00094     else
00095     {
00096       std::string keyword;
00097       stringstream >> keyword;
00098 
00099       // format
00100       if (keyword == "format")
00101       {
00102         std::string format_string, version;
00103         char space_format_format_string, space_format_string_version;
00104         stringstream >> space_format_format_string >> std::ws >> format_string >> space_format_string_version >> std::ws >> version >> std::ws;
00105         if (!stringstream || 
00106             !stringstream.eof () || 
00107             !isspace (space_format_format_string) || 
00108             !isspace (space_format_string_version))
00109         {
00110           if (error_callback_)
00111             error_callback_ (line_number_, "parse error");
00112           return false;
00113         }
00114         if (format_string == "ascii")
00115         {
00116           format = ascii_format;
00117         }
00118         else if (format_string == "binary_big_endian")
00119         {
00120           format = binary_big_endian_format;
00121         }
00122         else if (format_string == "binary_little_endian")
00123         {
00124           format = binary_little_endian_format;
00125         }
00126         else
00127         {
00128           if (error_callback_)
00129           {
00130             error_callback_ (line_number_, "parse error");
00131           }
00132           return false;
00133         }
00134         if (version != "1.0")
00135         {
00136           if (error_callback_)
00137           {
00138             error_callback_ (line_number_, "version '" + version + "' is not supported");
00139           }
00140           return false;
00141         }
00142         if (number_of_format_statements > 0)
00143         {
00144           if (error_callback_)
00145           {
00146             error_callback_ (line_number_, "parse error");
00147           }
00148           return false;
00149         }
00150         ++number_of_format_statements;
00151         if (format_callback_)
00152         {
00153           format_callback_ (format, version);
00154         }
00155       }
00156       // element
00157       else if (keyword == "element")
00158       {
00159         std::string name;
00160         std::size_t count;
00161         char space_element_name, space_name_count;
00162         stringstream >> space_element_name >> std::ws >> name >> space_name_count >> std::ws >> count >> std::ws;
00163         if (!stringstream || 
00164             !stringstream.eof () || 
00165             !isspace (space_element_name) || 
00166             !isspace (space_name_count))
00167         {
00168           if (error_callback_)
00169           {
00170             error_callback_ (line_number_, "parse error");
00171           }
00172           return false;
00173         }
00174         std::vector< boost::shared_ptr<element> >::const_iterator iterator;
00175         for (iterator = elements.begin (); iterator != elements.end (); ++iterator)
00176         {
00177           const struct element& element = *(iterator->get ());
00178           if (element.name == name)
00179           {
00180             break;
00181           }
00182         }
00183         if (iterator != elements.end ())
00184         {
00185           if (error_callback_)
00186           {
00187             error_callback_ (line_number_, "parse error");
00188           }
00189           return false;
00190         }
00191         ++number_of_element_statements;
00192         element_callbacks_type element_callbacks;
00193         if (element_definition_callbacks_)
00194         {
00195           element_callbacks = element_definition_callbacks_ (name, count);
00196         }
00197         boost::shared_ptr<element> element_ptr (new element (name, 
00198                                                                 count, 
00199                                                                 boost::get<0>(element_callbacks), 
00200                                                                 boost::get<1>(element_callbacks)));
00201         elements.push_back (boost::shared_ptr<element>(element_ptr));
00202         current_element_ = element_ptr.get ();
00203       }
00204 
00205       // property
00206       else if (keyword == "property")
00207       {
00208         std::string type_or_list;
00209         char space_property_type_or_list;
00210         stringstream >> space_property_type_or_list >> std::ws >> type_or_list;
00211         if (!stringstream || !isspace (space_property_type_or_list))
00212         {
00213           if (error_callback_)
00214           {
00215             error_callback_ (line_number_, "parse error");
00216           }
00217           return false;
00218         }
00219         if (type_or_list != "list") {
00220           std::string name;
00221           std::string& type = type_or_list;
00222           char space_type_name;
00223           stringstream >> space_type_name >> std::ws >> name >> std::ws;
00224           if (!stringstream || !isspace (space_type_name))
00225           {
00226             if (error_callback_)
00227             {
00228               error_callback_ (line_number_, "parse error");
00229             }
00230             return false;
00231           }
00232           if (number_of_element_statements == 0)
00233           {
00234             if (error_callback_)
00235             {
00236               error_callback_ (line_number_, "parse error");
00237             }
00238             return false;
00239           }
00240           std::vector< boost::shared_ptr<property> >::const_iterator iterator;
00241           for (iterator = current_element_->properties.begin (); 
00242                iterator != current_element_->properties.end (); 
00243                ++iterator)
00244           {
00245             const struct property& property = *(iterator->get ());
00246             if (property.name == name)
00247               break;
00248           }
00249           if (iterator != current_element_->properties.end ())
00250           {
00251             if (error_callback_)
00252               error_callback_ (line_number_, "parse error");
00253             return false;
00254           }
00255           if ((type == type_traits<int8>::name ()) || (type == type_traits<int8>::old_name ()))
00256           {
00257             parse_scalar_property_definition<int8>(name);
00258           }
00259           else if ((type == type_traits<int16>::name ()) || (type == type_traits<int16>::old_name ()))
00260           {
00261             parse_scalar_property_definition<int16>(name);
00262           }
00263           else if ((type == type_traits<int32>::name ()) || (type == type_traits<int32>::old_name ()))
00264           {
00265             parse_scalar_property_definition<int32>(name);
00266           }
00267           else if ((type == type_traits<uint8>::name ()) || (type == type_traits<uint8>::old_name ()))
00268           {
00269             parse_scalar_property_definition<uint8>(name);
00270           }
00271           else if ((type == type_traits<uint16>::name ()) || (type == type_traits<uint16>::old_name ()))
00272           {
00273             parse_scalar_property_definition<uint16>(name);
00274           }
00275           else if ((type == type_traits<uint32>::name ()) || (type == type_traits<uint32>::old_name ()))
00276           {
00277             parse_scalar_property_definition<uint32>(name);
00278           }
00279           else if ((type == type_traits<float32>::name ()) || (type == type_traits<float32>::old_name ()))
00280           {
00281             parse_scalar_property_definition<float32>(name);
00282           }
00283           else if ((type == type_traits<float64>::name ()) || (type == type_traits<float64>::old_name ()))
00284           {
00285             parse_scalar_property_definition<float64>(name);
00286           }
00287           else
00288           {
00289             if (error_callback_)
00290             {
00291               error_callback_ (line_number_, "parse error");
00292             }
00293             return false;
00294           }
00295           ++number_of_property_statements;
00296         }
00297         else
00298         {
00299           std::string name;
00300           std::string size_type_string, scalar_type_string;
00301           char space_list_size_type, space_size_type_scalar_type, space_scalar_type_name;
00302           stringstream >> space_list_size_type >> std::ws >> size_type_string >> space_size_type_scalar_type >> std::ws >> scalar_type_string >> space_scalar_type_name >> std::ws >> name >> std::ws;
00303           if (!stringstream || 
00304               !isspace (space_list_size_type) || 
00305               !isspace (space_size_type_scalar_type) || 
00306               !isspace (space_scalar_type_name))
00307           {
00308             if (error_callback_)
00309               error_callback_ (line_number_, "parse error");
00310             return false;
00311           }
00312           if (number_of_element_statements == 0)
00313           {
00314             if (error_callback_)
00315               error_callback_ (line_number_, "parse error");
00316             return false;
00317           }
00318           std::vector< boost::shared_ptr<property> >::const_iterator iterator;
00319           for (iterator = current_element_->properties.begin (); 
00320                iterator != current_element_->properties.end (); 
00321                ++iterator) 
00322           {
00323             const struct property& property = *(iterator->get ());
00324             if (property.name == name)
00325               break;
00326           }
00327           if (iterator != current_element_->properties.end ())
00328           {
00329             if (error_callback_)
00330               error_callback_ (line_number_, "parse error");
00331             return false;
00332           }
00333           if ((size_type_string == type_traits<uint8>::name ()) || (size_type_string == type_traits<uint8>::old_name ()))
00334           {
00335             typedef uint8 size_type;
00336             if ((scalar_type_string == type_traits<int8>::name ()) || (scalar_type_string == type_traits<int8>::old_name ()))
00337             {
00338               parse_list_property_definition<size_type, int8>(name);
00339             }
00340             else if ((scalar_type_string == type_traits<int16>::name ()) || (scalar_type_string == type_traits<int16>::old_name ()))
00341             {
00342               parse_list_property_definition<size_type, int16>(name);
00343             }
00344             else if ((scalar_type_string == type_traits<int32>::name ()) || (scalar_type_string == type_traits<int32>::old_name ()))
00345             {
00346               parse_list_property_definition<size_type, int32>(name);
00347             }
00348             else if ((scalar_type_string == type_traits<uint8>::name ()) || (scalar_type_string == type_traits<uint8>::old_name ()))
00349             {
00350               parse_list_property_definition<size_type, uint8>(name);
00351             }
00352             else if ((scalar_type_string == type_traits<uint16>::name ()) || (scalar_type_string == type_traits<uint16>::old_name ()))
00353             {
00354               parse_list_property_definition<size_type, uint16>(name);
00355             }
00356             else if ((scalar_type_string == type_traits<uint32>::name ()) || (scalar_type_string == type_traits<uint32>::old_name ()))
00357             {
00358               parse_list_property_definition<size_type, uint32>(name);
00359             }
00360             else if ((scalar_type_string == type_traits<float32>::name ()) || (scalar_type_string == type_traits<float32>::old_name ()))
00361             {
00362               parse_list_property_definition<size_type, float32>(name);
00363             }
00364             else if ((scalar_type_string == type_traits<float64>::name ()) || (scalar_type_string == type_traits<float64>::old_name ()))
00365             {
00366               parse_list_property_definition<size_type, float64>(name);
00367             }
00368             else
00369             {
00370               if (error_callback_)
00371               {
00372                 error_callback_ (line_number_, "parse error");
00373               }
00374               return false;
00375             }
00376           }
00377           else if ((size_type_string == type_traits<uint16>::name ()) || (size_type_string == type_traits<uint16>::old_name ()))
00378           {
00379             typedef uint16 size_type;
00380             if ((scalar_type_string == type_traits<int8>::name ()) || (scalar_type_string == type_traits<int8>::old_name ()))
00381             {
00382               parse_list_property_definition<size_type, int8>(name);
00383             }
00384             else if ((scalar_type_string == type_traits<int16>::name ()) || (scalar_type_string == type_traits<int16>::old_name ()))
00385             {
00386               parse_list_property_definition<size_type, int16>(name);
00387             }
00388             else if ((scalar_type_string == type_traits<int32>::name ()) || (scalar_type_string == type_traits<int32>::old_name ()))
00389             {
00390               parse_list_property_definition<size_type, int32>(name);
00391             }
00392             else if ((scalar_type_string == type_traits<uint8>::name ()) || (scalar_type_string == type_traits<uint8>::old_name ()))
00393             {
00394               parse_list_property_definition<size_type, uint8>(name);
00395             }
00396             else if ((scalar_type_string == type_traits<uint16>::name ()) || (scalar_type_string == type_traits<uint16>::old_name ()))
00397             {
00398               parse_list_property_definition<size_type, uint16>(name);
00399             }
00400             else if ((scalar_type_string == type_traits<uint32>::name ()) || (scalar_type_string == type_traits<uint32>::old_name ()))
00401             {
00402               parse_list_property_definition<size_type, uint32>(name);
00403             }
00404             else if ((scalar_type_string == type_traits<float32>::name ()) || (scalar_type_string == type_traits<float32>::old_name ()))
00405             {
00406               parse_list_property_definition<size_type, float32>(name);
00407             }
00408             else if ((scalar_type_string == type_traits<float64>::name ()) || (scalar_type_string == type_traits<float64>::old_name ()))
00409             {
00410               parse_list_property_definition<size_type, float64>(name);
00411             }
00412             else
00413             {
00414               if (error_callback_)
00415                 error_callback_ (line_number_, "parse error");
00416               return false;
00417             }
00418           }
00419           else if ((size_type_string == type_traits<uint32>::name ()) || (size_type_string == type_traits<uint32>::old_name ()))
00420           {
00421             typedef uint32 size_type;
00422             if ((scalar_type_string == type_traits<int8>::name ()) || (scalar_type_string == type_traits<int8>::old_name ()))
00423             {
00424               parse_list_property_definition<size_type, int8>(name);
00425             }
00426             else if ((scalar_type_string == type_traits<int16>::name ()) || (scalar_type_string == type_traits<int16>::old_name ()))
00427             {
00428               parse_list_property_definition<size_type, int16>(name);
00429             }
00430             else if ((scalar_type_string == type_traits<int32>::name ()) || (scalar_type_string == type_traits<int32>::old_name ()))
00431             {
00432               parse_list_property_definition<size_type, int32>(name);
00433             }
00434             else if ((scalar_type_string == type_traits<uint8>::name ()) || (scalar_type_string == type_traits<uint8>::old_name ()))
00435             {
00436               parse_list_property_definition<size_type, uint8>(name);
00437             }
00438             else if ((scalar_type_string == type_traits<uint16>::name ()) || (scalar_type_string == type_traits<uint16>::old_name ()))
00439             {
00440               parse_list_property_definition<size_type, uint16>(name);
00441             }
00442             else if ((scalar_type_string == type_traits<uint32>::name ()) || (scalar_type_string == type_traits<uint32>::old_name ()))
00443             {
00444               parse_list_property_definition<size_type, uint32>(name);
00445             }
00446             else if ((scalar_type_string == type_traits<float32>::name ()) || (scalar_type_string == type_traits<float32>::old_name ()))
00447             {
00448               parse_list_property_definition<size_type, float32>(name);
00449             }
00450             else if ((scalar_type_string == type_traits<float64>::name ()) || (scalar_type_string == type_traits<float64>::old_name ()))
00451             {
00452               parse_list_property_definition<size_type, float64>(name);
00453             }
00454             else
00455             {
00456               if (error_callback_)
00457                 error_callback_ (line_number_, "parse error");
00458               return false;
00459             }
00460           }
00461           else
00462           {
00463             if (error_callback_)
00464               error_callback_ (line_number_, "parse error");
00465             return false;
00466           }
00467           ++number_of_property_statements;
00468         }
00469       }
00470 
00471       // comment
00472       else if (keyword == "comment")
00473       {
00474         if (comment_callback_)
00475           comment_callback_ (line);
00476         ++number_of_comment_statements;
00477       }
00478 
00479       // obj_info
00480       else if (keyword == "obj_info")
00481       {
00482         if (obj_info_callback_)
00483           obj_info_callback_ (line);
00484         ++number_of_obj_info_statements;
00485       }
00486 
00487       // end_header
00488       else if (keyword == "end_header")
00489       {
00490         if (end_header_callback_)
00491         {
00492           if (end_header_callback_ () == false)
00493             return true;
00494         }
00495         break;
00496       }
00497       // unknown keyword
00498       else
00499       {
00500         if (warning_callback_)
00501           warning_callback_ (line_number_, "ignoring line '" + line + "'");
00502       }
00503     }
00504   }
00505 
00506   if (number_of_format_statements == 0)
00507   {
00508     if (error_callback_) 
00509      error_callback_ (line_number_, "parse error");
00510     return false;
00511   }
00512 
00513   // ascii
00514   if (format == ascii_format)
00515   {
00516     for (std::vector< boost::shared_ptr<element> >::const_iterator element_iterator = elements.begin (); 
00517          element_iterator != elements.end (); 
00518          ++element_iterator)
00519     {
00520       struct element& element = *(element_iterator->get ());
00521       for (std::size_t element_index = 0; element_index < element.count; ++element_index)
00522       {
00523         if (element.begin_element_callback) 
00524           element.begin_element_callback ();
00525         if (!std::getline (istream, line))
00526         {
00527           if (error_callback_)
00528             error_callback_ (line_number_, "parse error");
00529           return false;
00530         }
00531         ++line_number_;
00532         std::istringstream stringstream (line);
00533         stringstream.unsetf (std::ios_base::skipws);
00534         stringstream >> std::ws;
00535         for (std::vector< boost::shared_ptr<property> >::const_iterator property_iterator = element.properties.begin (); 
00536              property_iterator != element.properties.end (); 
00537              ++property_iterator)
00538         {
00539           struct property& property = *(property_iterator->get ());
00540           if (property.parse (*this, format, stringstream) == false)
00541             return false;
00542         }
00543         if (!stringstream.eof ())
00544         {
00545           if (error_callback_)
00546             error_callback_ (line_number_, "parse error");
00547           return false;
00548         }
00549         if (element.end_element_callback)
00550           element.end_element_callback ();
00551       }
00552     }
00553     istream >> std::ws;
00554     if (istream.fail () || !istream.eof () || istream.bad ())
00555     {
00556       if (error_callback_)
00557         error_callback_ (line_number_, "parse error");
00558       return false;
00559     }
00560     return true;
00561   }
00562 
00563   // binary
00564   else
00565   {
00566     std::streampos data_start = istream.tellg ();
00567     istream.close ();
00568     istream.open (filename.c_str (), std::ios::in | std::ios::binary);
00569     istream.seekg (data_start);
00570 
00571     for (std::vector< boost::shared_ptr<element> >::const_iterator element_iterator = elements.begin (); 
00572          element_iterator != elements.end (); 
00573          ++element_iterator)
00574     {
00575       struct element& element = *(element_iterator->get ());
00576       for (std::size_t element_index = 0; element_index < element.count; ++element_index)
00577       {
00578         if (element.begin_element_callback) {
00579           element.begin_element_callback ();
00580         }
00581         for (std::vector< boost::shared_ptr<property> >::const_iterator property_iterator = element.properties.begin (); 
00582              property_iterator != element.properties.end (); 
00583              ++property_iterator)
00584         {
00585           struct property& property = *(property_iterator->get ());
00586           if (property.parse (*this, format, istream) == false)
00587           {
00588             return false;
00589           }
00590         }
00591         if (element.end_element_callback)
00592         {
00593           element.end_element_callback ();
00594         }
00595       }
00596     }
00597     if (istream.fail () || (istream.rdbuf ()->sgetc () != std::char_traits<char>::eof ()) || istream.bad ())
00598     {
00599       if (error_callback_)
00600       {
00601         error_callback_ (line_number_, "parse error");
00602       }
00603       return false;
00604     }
00605     return true;
00606   }
00607 }


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