ply_parser.h
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) 2010-2011, 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: ply_parser.h 5323 2012-03-27 12:57:27Z bouffa $
00038  *
00039  */
00040 
00041 #ifndef PCL_IO_PLY_PLY_PARSER_H
00042 #define PCL_IO_PLY_PLY_PARSER_H
00043 
00044 #include <fstream>
00045 #include <iostream>
00046 #include <istream>
00047 #include <sstream>
00048 #include <string>
00049 #include <vector>
00050 
00051 #include <boost/function.hpp>
00052 #include <boost/tuple/tuple.hpp>
00053 #include <boost/shared_ptr.hpp>
00054 #include <boost/mpl/fold.hpp>
00055 #include <boost/mpl/inherit.hpp>
00056 #include <boost/mpl/inherit_linearly.hpp>
00057 #include <boost/mpl/joint_view.hpp>
00058 #include <boost/mpl/transform.hpp>
00059 #include <boost/mpl/vector.hpp>
00060 
00061 #include <pcl/io/ply/ply.h>
00062 #include <pcl/io/ply/io_operators.h>
00063 #include <pcl/pcl_macros.h>
00064 
00065 #ifdef BUILD_Maintainer
00066 #  if defined __GNUC__
00067 #    if __GNUC__ == 4 && __GNUC_MINOR__ > 3
00068 #      pragma GCC diagnostic ignored "-Weffc++"
00069 #      pragma GCC diagnostic ignored "-pedantic"
00070 #    else
00071 #      pragma GCC system_header 
00072 #    endif
00073 #  elif defined _MSC_VER
00074 #    pragma warning(push, 1)
00075 #  endif
00076 #endif
00077 
00078 namespace pcl
00079 {
00080   namespace io
00081   {
00082     namespace ply
00083     {
00090       class PCL_EXPORTS ply_parser
00091       {
00092         public:
00093 
00094           typedef boost::function<void (std::size_t, const std::string&)> info_callback_type;
00095           typedef boost::function<void (std::size_t, const std::string&)> warning_callback_type;
00096           typedef boost::function<void (std::size_t, const std::string&)> error_callback_type;
00097          
00098           typedef boost::function<void ()> magic_callback_type;
00099           typedef boost::function<void (format_type, const std::string&)> format_callback_type;
00100           typedef boost::function<void (const std::string&)> comment_callback_type;
00101           typedef boost::function<void (const std::string&)> obj_info_callback_type;
00102           typedef boost::function<bool ()> end_header_callback_type;
00103          
00104           typedef boost::function<void ()> begin_element_callback_type;
00105           typedef boost::function<void ()> end_element_callback_type;
00106           typedef boost::tuple<begin_element_callback_type, end_element_callback_type> element_callbacks_type;
00107           typedef boost::function<element_callbacks_type (const std::string&, std::size_t)> element_definition_callback_type;
00108          
00109           template <typename ScalarType>
00110           struct scalar_property_callback_type
00111           {
00112             typedef boost::function<void (ScalarType)> type;
00113           };
00114 
00115           template <typename ScalarType>
00116           struct scalar_property_definition_callback_type
00117           {
00118             typedef typename scalar_property_callback_type<ScalarType>::type scalar_property_callback_type;
00119             typedef boost::function<scalar_property_callback_type (const std::string&, const std::string&)> type;
00120           };
00121        
00122           typedef boost::mpl::vector<int8, int16, int32, uint8, uint16, uint32, float32, float64> scalar_types;
00123 
00124           class scalar_property_definition_callbacks_type
00125           {
00126             private:
00127               template <typename T>
00128               struct callbacks_element
00129               {
00130 //                callbacks_element () : callback ();
00131                 typedef T scalar_type;
00132                 typename scalar_property_definition_callback_type<scalar_type>::type callback;
00133               };
00134              
00135               typedef boost::mpl::inherit_linearly<
00136                 scalar_types,
00137                 boost::mpl::inherit<
00138                 boost::mpl::_1,
00139                 callbacks_element<boost::mpl::_2>
00140                 >
00141                 >::type callbacks;
00142               callbacks callbacks_;
00143              
00144             public:
00145               template <typename ScalarType>
00146               const typename scalar_property_definition_callback_type<ScalarType>::type&
00147               get () const
00148               {
00149                 return (static_cast<const callbacks_element<ScalarType>&> (callbacks_).callback);
00150               }
00151              
00152               template <typename ScalarType>
00153               typename scalar_property_definition_callback_type<ScalarType>::type&
00154               get ()
00155               {
00156                 return (static_cast<callbacks_element<ScalarType>&> (callbacks_).callback);
00157               }
00158              
00159               template <typename ScalarType>
00160               friend typename scalar_property_definition_callback_type<ScalarType>::type&
00161               at (scalar_property_definition_callbacks_type& scalar_property_definition_callbacks)
00162               {
00163                 return (scalar_property_definition_callbacks.get<ScalarType> ());
00164               }
00165            
00166               template <typename ScalarType>
00167               friend const typename scalar_property_definition_callback_type<ScalarType>::type&
00168               at (const scalar_property_definition_callbacks_type& scalar_property_definition_callbacks)
00169               {
00170                 return (scalar_property_definition_callbacks.get<ScalarType> ());
00171               }
00172           };
00173 
00174           template <typename SizeType, typename ScalarType>
00175           struct list_property_begin_callback_type
00176           {
00177             typedef boost::function<void (SizeType)> type;
00178           };
00179          
00180           template <typename SizeType, typename ScalarType>
00181           struct list_property_element_callback_type
00182           {
00183             typedef boost::function<void (ScalarType)> type;
00184           };
00185        
00186           template <typename SizeType, typename ScalarType>
00187           struct list_property_end_callback_type
00188           {
00189             typedef boost::function<void ()> type;
00190           };
00191 
00192           template <typename SizeType, typename ScalarType>
00193           struct list_property_definition_callback_type
00194           {
00195             typedef typename list_property_begin_callback_type<SizeType, ScalarType>::type list_property_begin_callback_type;
00196             typedef typename list_property_element_callback_type<SizeType, ScalarType>::type list_property_element_callback_type;
00197             typedef typename list_property_end_callback_type<SizeType, ScalarType>::type list_property_end_callback_type;
00198             typedef boost::function<
00199             boost::tuple<
00200             list_property_begin_callback_type,
00201               list_property_element_callback_type,
00202               list_property_end_callback_type
00203               > (const std::string&, const std::string&)> type;
00204           };
00205 
00206           typedef boost::mpl::vector<uint8, uint16, uint32> size_types;
00207      
00208           class list_property_definition_callbacks_type
00209           {
00210             private:
00211               template <typename T> struct pair_with : boost::mpl::pair<T,boost::mpl::_> {};
00212               template<typename Sequence1, typename Sequence2>
00213           
00214                 struct sequence_product :
00215                   boost::mpl::fold<Sequence1, boost::mpl::vector0<>,
00216                     boost::mpl::joint_view<
00217                       boost::mpl::_1,boost::mpl::transform<Sequence2, pair_with<boost::mpl::_2> > > >
00218                 {};
00219 
00220               template <typename T>
00221               struct callbacks_element
00222               {
00223                 typedef typename T::first size_type;
00224                 typedef typename T::second scalar_type;
00225                 typename list_property_definition_callback_type<size_type, scalar_type>::type callback;
00226               };
00227            
00228               typedef boost::mpl::inherit_linearly<sequence_product<size_types, scalar_types>::type, boost::mpl::inherit<boost::mpl::_1, callbacks_element<boost::mpl::_2> > >::type callbacks;
00229               callbacks callbacks_;
00230      
00231             public:
00232               template <typename SizeType, typename ScalarType>
00233               typename list_property_definition_callback_type<SizeType, ScalarType>::type&
00234               get ()
00235               {
00236                 return (static_cast<callbacks_element<boost::mpl::pair<SizeType, ScalarType> >&> (callbacks_).callback);
00237               }
00238 
00239               template <typename SizeType, typename ScalarType>
00240               const typename list_property_definition_callback_type<SizeType, ScalarType>::type&
00241               get () const
00242               {
00243                 return (static_cast<const callbacks_element<boost::mpl::pair<SizeType, ScalarType> >&> (callbacks_).callback);
00244               }
00245 
00246               template <typename SizeType, typename ScalarType>
00247               friend typename list_property_definition_callback_type<SizeType, ScalarType>::type&
00248               at (list_property_definition_callbacks_type& list_property_definition_callbacks)
00249               {
00250                 return (list_property_definition_callbacks.get<SizeType, ScalarType> ());
00251               }
00252            
00253               template <typename SizeType, typename ScalarType>
00254               friend const typename list_property_definition_callback_type<SizeType, ScalarType>::type&
00255               at (const list_property_definition_callbacks_type& list_property_definition_callbacks)
00256               {
00257                 return (list_property_definition_callbacks.get<SizeType, ScalarType> ());
00258               }
00259           };
00260 
00261           inline void
00262           info_callback (const info_callback_type& info_callback);
00263 
00264           inline void
00265           warning_callback (const warning_callback_type& warning_callback);
00266 
00267           inline void
00268           error_callback (const error_callback_type& error_callback);
00269 
00270           inline void
00271           magic_callback (const magic_callback_type& magic_callback);
00272 
00273           inline void
00274           format_callback (const format_callback_type& format_callback);
00275 
00276           inline void
00277           element_definition_callback (const element_definition_callback_type& element_definition_callback);
00278 
00279           inline void
00280           scalar_property_definition_callbacks (const scalar_property_definition_callbacks_type& scalar_property_definition_callbacks);
00281 
00282           inline void
00283           list_property_definition_callbacks (const list_property_definition_callbacks_type& list_property_definition_callbacks);
00284 
00285           inline void
00286           comment_callback (const comment_callback_type& comment_callback);
00287 
00288           inline void
00289           obj_info_callback (const obj_info_callback_type& obj_info_callback);
00290 
00291           inline void
00292           end_header_callback (const end_header_callback_type& end_header_callback);
00293 
00294           typedef int flags_type;
00295           enum flags { };
00296 
00297           ply_parser (flags_type flags = 0) : 
00298             flags_ (flags), 
00299             comment_callback_ (), obj_info_callback_ (), end_header_callback_ (), 
00300             line_number_ (0), current_element_ ()
00301           {}
00302               
00303           bool parse (const std::string& filename);
00304           //inline bool parse (const std::string& filename);
00305 
00306         private:
00307             
00308           struct property
00309           {
00310             property (const std::string& name) : name (name) {}
00311             virtual ~property () {}
00312             virtual bool parse (class ply_parser& ply_parser, format_type format, std::istream& istream) = 0;
00313             std::string name;
00314           };
00315             
00316           template <typename ScalarType>
00317           struct scalar_property : public property
00318           {
00319             typedef ScalarType scalar_type;
00320             typedef typename scalar_property_callback_type<scalar_type>::type callback_type;
00321             scalar_property (const std::string& name, callback_type callback)
00322               : property (name)
00323               , callback (callback)
00324             {}
00325             bool parse (class ply_parser& ply_parser, 
00326                         format_type format, 
00327                         std::istream& istream) 
00328             { 
00329               return ply_parser.parse_scalar_property<scalar_type> (format, istream, callback); 
00330             }
00331             callback_type callback;
00332           };
00333 
00334           template <typename SizeType, typename ScalarType>
00335           struct list_property : public property
00336           {
00337             typedef SizeType size_type;
00338             typedef ScalarType scalar_type;
00339             typedef typename list_property_begin_callback_type<size_type, scalar_type>::type begin_callback_type;
00340             typedef typename list_property_element_callback_type<size_type, scalar_type>::type element_callback_type;
00341             typedef typename list_property_end_callback_type<size_type, scalar_type>::type end_callback_type;
00342             list_property (const std::string& name, 
00343                            begin_callback_type begin_callback, 
00344                            element_callback_type element_callback, 
00345                            end_callback_type end_callback)
00346               : property (name)
00347               , begin_callback (begin_callback)
00348               , element_callback (element_callback)
00349               , end_callback (end_callback)
00350             {}
00351             bool parse (class ply_parser& ply_parser, 
00352                         format_type format, 
00353                         std::istream& istream) 
00354             { 
00355               return ply_parser.parse_list_property<size_type, scalar_type> (format, 
00356                                                                              istream,
00357                                                                              begin_callback,
00358                                                                              element_callback,
00359                                                                              end_callback);
00360             }
00361             begin_callback_type begin_callback;
00362             element_callback_type element_callback;
00363             end_callback_type end_callback;
00364           };
00365         
00366           struct element
00367           {
00368             element (const std::string& name, 
00369                     std::size_t count, 
00370                     const begin_element_callback_type& begin_element_callback, 
00371                     const end_element_callback_type& end_element_callback)
00372               : name (name)
00373               , count (count)
00374               , begin_element_callback (begin_element_callback)
00375               , end_element_callback (end_element_callback)
00376               , properties ()
00377             {}
00378             std::string name;
00379             std::size_t count;
00380             begin_element_callback_type begin_element_callback;
00381             end_element_callback_type end_element_callback;
00382             std::vector<boost::shared_ptr<property> > properties;
00383           };
00384 
00385           flags_type flags_;
00386           
00387           info_callback_type info_callback_;
00388           warning_callback_type warning_callback_;
00389           error_callback_type error_callback_;
00390           
00391           magic_callback_type magic_callback_;
00392           format_callback_type format_callback_;
00393           element_definition_callback_type element_definition_callbacks_;
00394           scalar_property_definition_callbacks_type scalar_property_definition_callbacks_;
00395           list_property_definition_callbacks_type list_property_definition_callbacks_;
00396           comment_callback_type comment_callback_;
00397           obj_info_callback_type obj_info_callback_;
00398           end_header_callback_type end_header_callback_;
00399           
00400           template <typename ScalarType> inline void 
00401           parse_scalar_property_definition (const std::string& property_name);
00402 
00403           template <typename SizeType, typename ScalarType> inline void 
00404           parse_list_property_definition (const std::string& property_name);
00405           
00406           template <typename ScalarType> inline bool 
00407           parse_scalar_property (format_type format, 
00408                                  std::istream& istream, 
00409                                  const typename scalar_property_callback_type<ScalarType>::type& scalar_property_callback);
00410 
00411           template <typename SizeType, typename ScalarType> inline bool 
00412           parse_list_property (format_type format, 
00413                                std::istream& istream, 
00414                                const typename list_property_begin_callback_type<SizeType, ScalarType>::type& list_property_begin_callback, 
00415                                const typename list_property_element_callback_type<SizeType, ScalarType>::type& list_property_element_callback, 
00416                                const typename list_property_end_callback_type<SizeType, ScalarType>::type& list_property_end_callback);
00417             
00418           std::size_t line_number_;
00419           element* current_element_;
00420       };
00421     } // namespace ply
00422   } // namespace io
00423 } // namespace pcl
00424 
00425 /* inline bool pcl::io::ply::ply_parser::parse (const std::string& filename) */
00426 /* { */
00427 /*   std::ifstream ifstream (filename.c_str ()); */
00428 /*   return (parse (ifstream)); */
00429 /* } */
00430 
00431 inline void pcl::io::ply::ply_parser::info_callback (const info_callback_type& info_callback)
00432 {
00433   info_callback_ = info_callback;
00434 }
00435     
00436 inline void pcl::io::ply::ply_parser::warning_callback (const warning_callback_type& warning_callback)
00437 {
00438   warning_callback_ = warning_callback;
00439 }
00440     
00441 inline void pcl::io::ply::ply_parser::error_callback (const error_callback_type& error_callback)
00442 {
00443   error_callback_ = error_callback;
00444 }
00445     
00446 inline void pcl::io::ply::ply_parser::magic_callback (const magic_callback_type& magic_callback)
00447 {
00448   magic_callback_ = magic_callback;
00449 }
00450     
00451 inline void pcl::io::ply::ply_parser::format_callback (const format_callback_type& format_callback)
00452 {
00453   format_callback_ = format_callback;
00454 }
00455     
00456 inline void pcl::io::ply::ply_parser::element_definition_callback (const element_definition_callback_type& element_definition_callback)
00457 {
00458   element_definition_callbacks_ = element_definition_callback;
00459 }
00460     
00461 inline void pcl::io::ply::ply_parser::scalar_property_definition_callbacks (const scalar_property_definition_callbacks_type& scalar_property_definition_callbacks)
00462 {
00463   scalar_property_definition_callbacks_ = scalar_property_definition_callbacks;
00464 }
00465     
00466 inline void pcl::io::ply::ply_parser::list_property_definition_callbacks (const list_property_definition_callbacks_type& list_property_definition_callbacks)
00467 {
00468   list_property_definition_callbacks_ = list_property_definition_callbacks;
00469 }
00470     
00471 inline void pcl::io::ply::ply_parser::comment_callback (const comment_callback_type& comment_callback)
00472 {
00473   comment_callback_ = comment_callback;
00474 }
00475 
00476 inline void pcl::io::ply::ply_parser::obj_info_callback (const obj_info_callback_type& obj_info_callback)
00477 {
00478   obj_info_callback_ = obj_info_callback;
00479 }
00480 
00481 inline void pcl::io::ply::ply_parser::end_header_callback (const end_header_callback_type& end_header_callback)
00482 {
00483   end_header_callback_ = end_header_callback;
00484 }
00485 
00486 template <typename ScalarType>
00487 inline void pcl::io::ply::ply_parser::parse_scalar_property_definition (const std::string& property_name)
00488 {
00489   typedef ScalarType scalar_type;
00490   typename scalar_property_definition_callback_type<scalar_type>::type& scalar_property_definition_callback = 
00491     scalar_property_definition_callbacks_.get<scalar_type> ();
00492   typename scalar_property_callback_type<scalar_type>::type scalar_property_callback;
00493   if (scalar_property_definition_callback)
00494   {
00495     scalar_property_callback = scalar_property_definition_callback (current_element_->name, property_name);
00496   }
00497   if (!scalar_property_callback)
00498   {
00499     if (warning_callback_)
00500     {
00501       warning_callback_ (line_number_, 
00502                         "property '" + std::string (type_traits<scalar_type>::name ()) + " " + 
00503                         property_name + "' of element '" + current_element_->name + "' is not handled");
00504     }
00505   }
00506   current_element_->properties.push_back (boost::shared_ptr<property> (new scalar_property<scalar_type> (property_name, scalar_property_callback)));
00507 }
00508 
00509 template <typename SizeType, typename ScalarType>
00510 inline void pcl::io::ply::ply_parser::parse_list_property_definition (const std::string& property_name)
00511 {
00512   typedef SizeType size_type;
00513   typedef ScalarType scalar_type;
00514   typename list_property_definition_callback_type<size_type, scalar_type>::type& list_property_definition_callback = 
00515     list_property_definition_callbacks_.get<size_type, scalar_type> ();
00516   typedef typename list_property_begin_callback_type<size_type, scalar_type>::type list_property_begin_callback_type;
00517   typedef typename list_property_element_callback_type<size_type, scalar_type>::type list_property_element_callback_type;
00518   typedef typename list_property_end_callback_type<size_type, scalar_type>::type list_property_end_callback_type;
00519   boost::tuple<list_property_begin_callback_type, list_property_element_callback_type, list_property_end_callback_type> list_property_callbacks;
00520   if (list_property_definition_callback)
00521   {
00522     list_property_callbacks = list_property_definition_callback (current_element_->name, property_name);
00523   }
00524   if (!boost::get<0> (list_property_callbacks) || !boost::get<1> (list_property_callbacks) || !boost::get<2> (list_property_callbacks))
00525   {
00526     if (warning_callback_)
00527     {
00528       warning_callback_ (line_number_, 
00529                         "property 'list " + std::string (type_traits<size_type>::name ()) + " " + 
00530                         std::string (type_traits<scalar_type>::name ()) + " " + 
00531                         property_name + "' of element '" + 
00532                         current_element_->name + "' is not handled");
00533     }
00534   }
00535   current_element_->properties.push_back (boost::shared_ptr<property> (
00536                                            new list_property<size_type, scalar_type> (
00537                                              property_name, 
00538                                              boost::get<0> (list_property_callbacks), 
00539                                              boost::get<1> (list_property_callbacks), 
00540                                              boost::get<2> (list_property_callbacks))));
00541 }
00542 
00543 template <typename ScalarType>
00544 inline bool pcl::io::ply::ply_parser::parse_scalar_property (format_type format, 
00545                                                              std::istream& istream, 
00546                                                              const typename scalar_property_callback_type<ScalarType>::type& scalar_property_callback)
00547 {
00548   using namespace io_operators;
00549   typedef ScalarType scalar_type;
00550   if (format == ascii_format)
00551   {
00552     scalar_type value = std::numeric_limits<scalar_type>::quiet_NaN ();
00553     char space = ' ';
00554     istream >> value;
00555     if (!istream.eof ())
00556       istream >> space >> std::ws;
00557     if (!istream || !isspace (space))
00558     {
00559       if (error_callback_)
00560         error_callback_ (line_number_, "parse error");
00561       return (false);
00562     }
00563     if (scalar_property_callback)
00564       scalar_property_callback (value);
00565     return (true);
00566   }
00567   else
00568   {
00569     scalar_type value = std::numeric_limits<scalar_type>::quiet_NaN ();
00570     istream.read (reinterpret_cast<char*> (&value), sizeof (scalar_type));
00571     if (!istream)
00572     {
00573       if (error_callback_)
00574         error_callback_ (line_number_, "parse error");
00575       return (false);
00576     }
00577     if (((format == binary_big_endian_format) && (host_byte_order == little_endian_byte_order)) ||
00578         ((format == binary_little_endian_format) && (host_byte_order == big_endian_byte_order)))
00579       swap_byte_order (value);
00580     if (scalar_property_callback)
00581       scalar_property_callback (value);
00582     return (true);
00583   }
00584 }
00585 
00586 template <typename SizeType, typename ScalarType>
00587 inline bool pcl::io::ply::ply_parser::parse_list_property (format_type format, std::istream& istream, 
00588                                                            const typename list_property_begin_callback_type<SizeType, ScalarType>::type& list_property_begin_callback, 
00589                                                            const typename list_property_element_callback_type<SizeType, ScalarType>::type& list_property_element_callback, 
00590                                                            const typename list_property_end_callback_type<SizeType, ScalarType>::type& list_property_end_callback)
00591 {
00592   using namespace io_operators;
00593   typedef SizeType size_type;
00594   typedef ScalarType scalar_type;
00595   if (format == ascii_format)
00596   {
00597     size_type size = std::numeric_limits<size_type>::infinity ();
00598     char space = ' ';
00599     istream >> size;
00600     if (!istream.eof ())
00601     {
00602       istream >> space >> std::ws;
00603     }
00604     if (!istream || !isspace (space))
00605     {
00606       if (error_callback_)
00607       {
00608         error_callback_ (line_number_, "parse error");
00609       }
00610       return (false);
00611     }
00612     if (list_property_begin_callback)
00613     {
00614       list_property_begin_callback (size);
00615     }
00616     for (std::size_t index = 0; index < size; ++index)
00617     {
00618       scalar_type value = std::numeric_limits<scalar_type>::quiet_NaN ();
00619       char space = ' ';
00620       istream >> value;
00621       if (!istream.eof ())
00622       {
00623         istream >> space >> std::ws;
00624       }
00625       if (!istream || !isspace (space))
00626       {
00627         if (error_callback_)
00628         {
00629           error_callback_ (line_number_, "parse error");
00630         }
00631         return (false);
00632       }
00633       if (list_property_element_callback)
00634       {
00635         list_property_element_callback (value);
00636       }
00637     }
00638     if (list_property_end_callback)
00639     {
00640       list_property_end_callback ();
00641     }
00642     return (true);
00643   }
00644   else
00645   {
00646     size_type size = std::numeric_limits<size_type>::infinity ();
00647     istream.read (reinterpret_cast<char*> (&size), sizeof (size_type));
00648     if (((format == binary_big_endian_format) && (host_byte_order == little_endian_byte_order)) || 
00649         ((format == binary_little_endian_format) && (host_byte_order == big_endian_byte_order)))
00650     {
00651       swap_byte_order (size);
00652     }
00653     if (!istream)
00654     {
00655       if (error_callback_)
00656       {
00657         error_callback_ (line_number_, "parse error");
00658       }
00659       return (false);
00660     }
00661     if (list_property_begin_callback)
00662     {
00663       list_property_begin_callback (size);
00664     }
00665     for (std::size_t index = 0; index < size; ++index) {
00666       scalar_type value  = std::numeric_limits<scalar_type>::quiet_NaN ();
00667       istream.read (reinterpret_cast<char*> (&value), sizeof (scalar_type));
00668       if (!istream) {
00669         if (error_callback_) {
00670           error_callback_ (line_number_, "parse error");
00671         }
00672         return (false);
00673       }
00674       if (((format == binary_big_endian_format) && (host_byte_order == little_endian_byte_order)) ||
00675           ((format == binary_little_endian_format) && (host_byte_order == big_endian_byte_order)))
00676       {
00677         swap_byte_order (value);
00678       }
00679       if (list_property_element_callback)
00680       {
00681         list_property_element_callback (value);
00682       }
00683     }
00684     if (list_property_end_callback)
00685     {
00686       list_property_end_callback ();
00687     }
00688     return (true);
00689   }
00690 }
00691 
00692 #ifdef BUILD_Maintainer
00693 #  if defined __GNUC__
00694 #    if __GNUC__ == 4 && __GNUC_MINOR__ > 3
00695 #      pragma GCC diagnostic warning "-Weffc++"
00696 #      pragma GCC diagnostic warning "-pedantic"
00697 #    endif
00698 #  elif defined _MSC_VER
00699 #    pragma warning(pop)
00700 #  endif
00701 #endif
00702 
00703 #endif // PCL_IO_PLY_PLY_PARSER_H


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