io_operators.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) 2012, Willow Garage, Inc.
00007  *  All rights reserved.
00008  *
00009  *  Redistribution and use in source and binary forms, with or without
00010  *  modification, are permitted provided that the following conditions
00011  *  are met:
00012  *
00013  *   * Redistributions of source code must retain the above copyright
00014  *     notice, this list of conditions and the following disclaimer.
00015  *   * Redistributions in binary form must reproduce the above
00016  *     copyright notice, this list of conditions and the following
00017  *     disclaimer in the documentation and/or other materials provided
00018  *     with the distribution.
00019  *   * Neither the name of Willow Garage, Inc. nor the names of its
00020  *     contributors may be used to endorse or promote products derived
00021  *     from this software without specific prior written permission.
00022  *
00023  *  THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
00024  *  "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
00025  *  LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
00026  *  FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
00027  *  COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
00028  *  INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
00029  *  BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
00030  *  LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
00031  *  CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
00032  *  LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
00033  *  ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
00034  *  POSSIBILITY OF SUCH DAMAGE.
00035  *  
00036  * $Id: io_operators.h 4252 2012-02-04 01:10:24Z nizar $
00037  *
00038  */
00039 
00040 #ifndef PCL_IO_PLY_IO_OPERATORS_H
00041 #define PCL_IO_PLY_IO_OPERATORS_H
00042 
00043 #include <istream>
00044 #include <limits>
00045 #include <ostream>
00046 
00047 namespace pcl
00048 {
00049   namespace io
00050   {
00051     namespace ply 
00052     {
00058       namespace io_operators 
00059       {
00060 
00061         inline std::istream& operator>> (std::istream& istream, int8 &value)
00062         {
00063           int16 tmp;
00064           if (istream >> tmp)
00065           {
00066             if (tmp <= std::numeric_limits<int8>::max ())
00067               value = static_cast<int8> (tmp);
00068             else
00069               istream.setstate (std::ios_base::failbit);
00070           }
00071           return (istream);
00072         }
00073 
00074         inline std::istream& operator>> (std::istream& istream, uint8 &value)
00075         {
00076           uint16 tmp;
00077           if (istream >> tmp)
00078           {
00079             if (tmp <= std::numeric_limits<uint8>::max ())
00080               value = static_cast<uint8> (tmp);
00081             else
00082               istream.setstate (std::ios_base::failbit);
00083           }
00084           return (istream);
00085         }
00086 
00087         inline std::ostream& operator<<(std::ostream& ostream, int8 value)
00088         {
00089           return (ostream << static_cast<int16> (value));
00090         }
00091 
00092         inline std::ostream& operator<<(std::ostream& ostream, uint8 value)
00093         {
00094           return (ostream << static_cast<uint16> (value));
00095         }
00096 
00097       } // namespace io_operators
00098     } // namespace ply
00099   } // namespace io
00100 } // namespace pcl
00101 
00102 #endif // PLY_IO_OPERATORS_H


pcl
Author(s): Open Perception
autogenerated on Mon Oct 6 2014 03:15:31