lzf_image_io.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) 2012-, Open Perception, Inc.
00006  *
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 the copyright holder(s) 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  */
00037 
00038 #ifndef PCL_LZF_IMAGE_IO_H_
00039 #define PCL_LZF_IMAGE_IO_H_
00040 
00041 #include <pcl/pcl_macros.h>
00042 #include <pcl/point_cloud.h>
00043 #include <vector>
00044 
00045 namespace pcl
00046 {
00047   namespace io
00048   {
00050     struct CameraParameters
00051     {
00053       double focal_length_x;
00055       double focal_length_y;
00057       double principal_point_x;
00059       double principal_point_y;
00060     };
00061 
00086     class PCL_EXPORTS LZFImageReader
00087     {
00088       public:
00090         LZFImageReader ();
00092         virtual ~LZFImageReader () {}
00093 
00097         bool
00098         readParameters (const std::string &filename);
00099 
00102         inline void
00103         setParameters (const CameraParameters &parameters)
00104         {
00105           parameters_ = parameters;
00106         }
00107 
00110         inline CameraParameters
00111         getParameters () const
00112         {
00113           return parameters_;
00114         }
00115 
00117         inline uint32_t
00118         getWidth () const
00119         {
00120           return (width_);
00121         }
00122 
00124         inline uint32_t
00125         getHeight () const
00126         {
00127           return (height_);
00128         }
00129 
00131         inline std::string
00132         getImageType () const
00133         {
00134           return (image_type_identifier_);
00135         }
00136 
00137       protected:
00141         virtual bool
00142         readParameters (std::istream&) { return (false); }
00143 
00149         bool
00150         loadImageBlob (const std::string &filename,
00151                        std::vector<char> &data,
00152                        uint32_t &uncompressed_size);
00153 
00159         bool
00160         decompress (const std::vector<char> &input, 
00161                     std::vector<char> &output); 
00162 
00164         uint32_t width_;
00165 
00167         uint32_t height_;
00168 
00170         std::string image_type_identifier_;
00171 
00173         CameraParameters parameters_;
00174     };
00175 
00186     class PCL_EXPORTS LZFDepth16ImageReader : public LZFImageReader
00187     {
00188       public:
00189         using LZFImageReader::readParameters;
00190 
00192         LZFDepth16ImageReader () 
00193           : LZFImageReader () 
00194           , z_multiplication_factor_ (0.001)      // Set default multiplication factor
00195         {}
00196 
00198         virtual ~LZFDepth16ImageReader () {}
00199 
00204         template <typename PointT> bool
00205         read (const std::string &filename, pcl::PointCloud<PointT> &cloud);
00206         
00212         template <typename PointT> bool
00213         readOMP (const std::string &filename, pcl::PointCloud<PointT> &cloud, 
00214                  unsigned int num_threads=0);
00215 
00220         virtual bool
00221         readParameters (std::istream& is);
00222 
00223       protected:
00227         double z_multiplication_factor_;
00228     };
00229 
00240     class PCL_EXPORTS LZFRGB24ImageReader : public LZFImageReader
00241     {
00242       public:
00243         using LZFImageReader::readParameters;
00244 
00246         LZFRGB24ImageReader () : LZFImageReader () {}
00248         virtual ~LZFRGB24ImageReader () {}
00249 
00254         template<typename PointT> bool
00255         read (const std::string &filename, pcl::PointCloud<PointT> &cloud);
00256         
00263         template <typename PointT> bool
00264         readOMP (const std::string &filename, pcl::PointCloud<PointT> &cloud, 
00265                  unsigned int num_threads=0);
00266 
00271         virtual bool
00272         readParameters (std::istream& is);
00273 
00274       protected:
00275     };
00276 
00287     class PCL_EXPORTS LZFYUV422ImageReader : public LZFRGB24ImageReader
00288     {
00289       public:
00290         using LZFRGB24ImageReader::readParameters;
00291 
00293         LZFYUV422ImageReader () : LZFRGB24ImageReader () {}
00295         ~LZFYUV422ImageReader () {}
00296 
00301         template<typename PointT> bool
00302         read (const std::string &filename, pcl::PointCloud<PointT> &cloud);
00303         
00310         template <typename PointT> bool
00311         readOMP (const std::string &filename, pcl::PointCloud<PointT> &cloud, 
00312                  unsigned int num_threads=0);
00313     };
00314 
00325     class PCL_EXPORTS LZFBayer8ImageReader : public LZFRGB24ImageReader
00326     {
00327       public:
00328         using LZFRGB24ImageReader::readParameters;
00329 
00331         LZFBayer8ImageReader () : LZFRGB24ImageReader () {}
00333         ~LZFBayer8ImageReader () {}
00334 
00339         template<typename PointT> bool
00340         read (const std::string &filename, pcl::PointCloud<PointT> &cloud);
00341 
00348         template <typename PointT> bool
00349         readOMP (const std::string &filename, pcl::PointCloud<PointT> &cloud, 
00350                  unsigned int num_threads=0);
00351     };
00352 
00377     class PCL_EXPORTS LZFImageWriter
00378     {
00379       public:
00381         LZFImageWriter () {}
00383         virtual ~LZFImageWriter () {}
00384 
00392         virtual bool
00393         write (const char* data,
00394                uint32_t width, uint32_t height,
00395                const std::string &filename) = 0;
00396 
00402         virtual bool
00403         writeParameters (const CameraParameters &parameters,
00404                          const std::string &filename) = 0;
00405 
00415         virtual bool
00416         write (const char* data,
00417                uint32_t width, uint32_t height,
00418                const CameraParameters &parameters,
00419                const std::string &filename_data,
00420                const std::string &filename_xml)
00421         {
00422           bool res1 = write (data, width, height, filename_data);
00423           bool res2 = writeParameters (parameters, filename_xml);
00424           return (res1 && res2);
00425         }
00426 
00438         bool
00439         writeParameter (const double &parameter, const std::string &tag, 
00440                         const std::string &filename);
00441       protected:
00448         bool
00449         saveImageBlob (const char* data, size_t data_size, 
00450                        const std::string &filename);
00451 
00463         uint32_t
00464         compress (const char* input, uint32_t input_size, 
00465                   uint32_t width, uint32_t height,
00466                   const std::string &image_type,
00467                   char *output);
00468     };
00469 
00480     class PCL_EXPORTS LZFDepth16ImageWriter : public LZFImageWriter
00481     {
00482       public:
00484         LZFDepth16ImageWriter () 
00485           : LZFImageWriter ()
00486           , z_multiplication_factor_ (0.001)      // Set default multiplication factor
00487         {}
00488 
00490         virtual ~LZFDepth16ImageWriter () {}
00491 
00499         virtual bool
00500         write (const char* data,
00501                uint32_t width, uint32_t height,
00502                const std::string &filename);
00503 
00516         virtual bool
00517         writeParameters (const CameraParameters &parameters,
00518                          const std::string &filename);
00519 
00520       protected:
00524         double z_multiplication_factor_;
00525     };
00526 
00537     class PCL_EXPORTS LZFRGB24ImageWriter : public LZFImageWriter
00538     {
00539       public:
00541         LZFRGB24ImageWriter () : LZFImageWriter () {}
00543         virtual ~LZFRGB24ImageWriter () {}
00544 
00552         virtual bool
00553         write (const char *data, 
00554                uint32_t width, uint32_t height,
00555                const std::string &filename);
00556 
00562         virtual bool
00563         writeParameters (const CameraParameters &parameters,
00564                          const std::string &filename);
00565 
00566       protected:
00567     };
00568 
00579     class PCL_EXPORTS LZFYUV422ImageWriter : public LZFRGB24ImageWriter
00580     {
00581       public:
00583         LZFYUV422ImageWriter () : LZFRGB24ImageWriter () {}
00585         virtual ~LZFYUV422ImageWriter () {}
00586 
00594         virtual bool
00595         write (const char *data, 
00596                uint32_t width, uint32_t height,
00597                const std::string &filename);
00598     };
00599 
00610     class PCL_EXPORTS LZFBayer8ImageWriter : public LZFRGB24ImageWriter
00611     {
00612       public:
00614         LZFBayer8ImageWriter () : LZFRGB24ImageWriter () {}
00616         virtual ~LZFBayer8ImageWriter () {}
00617 
00625         virtual bool
00626         write (const char *data, 
00627                uint32_t width, uint32_t height,
00628                const std::string &filename);
00629     };
00630   }
00631 }
00632 
00633 #include <pcl/io/impl/lzf_image_io.hpp>
00634 
00635 #endif  //#ifndef PCL_LZF_IMAGE_IO_H_


pcl
Author(s): Open Perception
autogenerated on Wed Aug 26 2015 15:25:20