Compression.cpp
Go to the documentation of this file.
00001 /*
00002 Copyright (c) 2010-2014, Mathieu Labbe - IntRoLab - Universite de Sherbrooke
00003 All rights reserved.
00004 
00005 Redistribution and use in source and binary forms, with or without
00006 modification, are permitted provided that the following conditions are met:
00007     * Redistributions of source code must retain the above copyright
00008       notice, this list of conditions and the following disclaimer.
00009     * Redistributions in binary form must reproduce the above copyright
00010       notice, this list of conditions and the following disclaimer in the
00011       documentation and/or other materials provided with the distribution.
00012     * Neither the name of the Universite de Sherbrooke nor the
00013       names of its contributors may be used to endorse or promote products
00014       derived from this software without specific prior written permission.
00015 
00016 THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" AND
00017 ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED
00018 WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE
00019 DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE FOR ANY
00020 DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES
00021 (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
00022 LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND
00023 ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT
00024 (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS
00025 SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
00026 */
00027 
00028 #include "rtabmap/core/Compression.h"
00029 #include <rtabmap/utilite/ULogger.h>
00030 #include <rtabmap/utilite/UConversion.h>
00031 #include <opencv2/opencv.hpp>
00032 
00033 #include <zlib.h>
00034 
00035 namespace rtabmap {
00036 
00037 // format : ".png" ".jpg" "" (empty is general)
00038 CompressionThread::CompressionThread(const cv::Mat & mat, const std::string & format) :
00039         uncompressedData_(mat),
00040         format_(format),
00041         image_(!format.empty()),
00042         compressMode_(true)
00043 {
00044         UASSERT(format.empty() || format.compare(".png") == 0 || format.compare(".jpg") == 0);
00045 }
00046 // assume image
00047 CompressionThread::CompressionThread(const cv::Mat & bytes, bool isImage) :
00048         compressedData_(bytes),
00049         image_(isImage),
00050         compressMode_(false)
00051 {}
00052 void CompressionThread::mainLoop()
00053 {
00054         if(compressMode_)
00055         {
00056                 if(!uncompressedData_.empty())
00057                 {
00058                         if(image_)
00059                         {
00060                                 compressedData_ = compressImage2(uncompressedData_, format_);
00061                         }
00062                         else
00063                         {
00064                                 compressedData_ = compressData2(uncompressedData_);
00065                         }
00066                 }
00067         }
00068         else // uncompress
00069         {
00070                 if(!compressedData_.empty())
00071                 {
00072                         if(image_)
00073                         {
00074                                 uncompressedData_ = uncompressImage(compressedData_);
00075                         }
00076                         else
00077                         {
00078                                 uncompressedData_ = uncompressData(compressedData_);
00079                         }
00080                 }
00081         }
00082         this->kill();
00083 }
00084 
00085 // ".png" or ".jpg"
00086 std::vector<unsigned char> compressImage(const cv::Mat & image, const std::string & format)
00087 {
00088         std::vector<unsigned char> bytes;
00089         if(!image.empty())
00090         {
00091                 cv::imencode(format, image, bytes);
00092         }
00093         return bytes;
00094 }
00095 
00096 // ".png" or ".jpg"
00097 cv::Mat compressImage2(const cv::Mat & image, const std::string & format)
00098 {
00099         std::vector<unsigned char> bytes = compressImage(image, format);
00100         if(bytes.size())
00101         {
00102                 return cv::Mat(1, (int)bytes.size(), CV_8UC1, bytes.data()).clone();
00103         }
00104         return cv::Mat();
00105 }
00106 
00107 cv::Mat uncompressImage(const cv::Mat & bytes)
00108 {
00109          cv::Mat image;
00110         if(!bytes.empty())
00111         {
00112 #if CV_MAJOR_VERSION>2 || (CV_MAJOR_VERSION >=2 && CV_MINOR_VERSION >=4)
00113                 image = cv::imdecode(bytes, cv::IMREAD_UNCHANGED);
00114 #else
00115                 image = cv::imdecode(bytes, -1);
00116 #endif
00117         }
00118         return image;
00119 }
00120 
00121 cv::Mat uncompressImage(const std::vector<unsigned char> & bytes)
00122 {
00123          cv::Mat image;
00124         if(bytes.size())
00125         {
00126 #if CV_MAJOR_VERSION>2 || (CV_MAJOR_VERSION >=2 && CV_MINOR_VERSION >=4)
00127                 image = cv::imdecode(bytes, cv::IMREAD_UNCHANGED);
00128 #else
00129                 image = cv::imdecode(bytes, -1);
00130 #endif
00131         }
00132         return image;
00133 }
00134 
00135 std::vector<unsigned char> compressData(const cv::Mat & data)
00136 {
00137         std::vector<unsigned char> bytes;
00138         if(!data.empty())
00139         {
00140                 uLong sourceLen = uLong(data.total())*uLong(data.elemSize());
00141                 uLong destLen = compressBound(sourceLen);
00142                 bytes.resize(destLen);
00143                 int errCode = compress(
00144                                                 (Bytef *)bytes.data(),
00145                                                 &destLen,
00146                                                 (const Bytef *)data.data,
00147                                                 sourceLen);
00148 
00149                 bytes.resize(destLen+3*sizeof(int));
00150                 *((int*)&bytes[destLen]) = data.rows;
00151                 *((int*)&bytes[destLen+sizeof(int)]) = data.cols;
00152                 *((int*)&bytes[destLen+2*sizeof(int)]) = data.type();
00153 
00154                 if(errCode == Z_MEM_ERROR)
00155                 {
00156                         UERROR("Z_MEM_ERROR : Insufficient memory.");
00157                 }
00158                 else if(errCode == Z_BUF_ERROR)
00159                 {
00160                         UERROR("Z_BUF_ERROR : The buffer dest was not large enough to hold the uncompressed data.");
00161                 }
00162         }
00163         return bytes;
00164 }
00165 
00166 cv::Mat compressData2(const cv::Mat & data)
00167 {
00168         cv::Mat bytes;
00169         if(!data.empty())
00170         {
00171                 uLong sourceLen = uLong(data.total())*uLong(data.elemSize());
00172                 uLong destLen = compressBound(sourceLen);
00173                 bytes = cv::Mat(1, destLen+3*sizeof(int), CV_8UC1);
00174                 int errCode = compress(
00175                                                 (Bytef *)bytes.data,
00176                                                 &destLen,
00177                                                 (const Bytef *)data.data,
00178                                                 sourceLen);
00179                 bytes = cv::Mat(bytes, cv::Rect(0,0, destLen+3*sizeof(int), 1));
00180                 *((int*)&bytes.data[destLen]) = data.rows;
00181                 *((int*)&bytes.data[destLen+sizeof(int)]) = data.cols;
00182                 *((int*)&bytes.data[destLen+2*sizeof(int)]) = data.type();
00183 
00184                 if(errCode == Z_MEM_ERROR)
00185                 {
00186                         UERROR("Z_MEM_ERROR : Insufficient memory.");
00187                 }
00188                 else if(errCode == Z_BUF_ERROR)
00189                 {
00190                         UERROR("Z_BUF_ERROR : The buffer dest was not large enough to hold the uncompressed data.");
00191                 }
00192         }
00193         return bytes;
00194 }
00195 
00196 cv::Mat uncompressData(const cv::Mat & bytes)
00197 {
00198         UASSERT(bytes.empty() || bytes.type() == CV_8UC1);
00199         return uncompressData(bytes.data, bytes.cols*bytes.rows);
00200 }
00201 
00202 cv::Mat uncompressData(const std::vector<unsigned char> & bytes)
00203 {
00204         return uncompressData(bytes.data(), (unsigned long)bytes.size());
00205 }
00206 
00207 cv::Mat uncompressData(const unsigned char * bytes, unsigned long size)
00208 {
00209         cv::Mat data;
00210         if(bytes && size>=3*sizeof(int))
00211         {
00212                 //last 3 int elements are matrix size and type
00213                 int height = *((int*)&bytes[size-3*sizeof(int)]);
00214                 int width = *((int*)&bytes[size-2*sizeof(int)]);
00215                 int type = *((int*)&bytes[size-1*sizeof(int)]);
00216 
00217                 // If the size is higher, it may be a wrong data format.
00218                 UASSERT_MSG(height>=0 && height<10000 &&
00219                                     width>=0 && width<10000,
00220                                     uFormat("size=%d, height=%d width=%d type=%d", size, height, width, type).c_str());
00221 
00222                 data = cv::Mat(height, width, type);
00223                 uLongf totalUncompressed = uLongf(data.total())*uLongf(data.elemSize());
00224 
00225                 int errCode = uncompress(
00226                                                 (Bytef*)data.data,
00227                                                 &totalUncompressed,
00228                                                 (const Bytef*)bytes,
00229                                                 uLong(size));
00230 
00231                 if(errCode == Z_MEM_ERROR)
00232                 {
00233                         UERROR("Z_MEM_ERROR : Insufficient memory.");
00234                 }
00235                 else if(errCode == Z_BUF_ERROR)
00236                 {
00237                         UERROR("Z_BUF_ERROR : The buffer dest was not large enough to hold the uncompressed data.");
00238                 }
00239                 else if(errCode == Z_DATA_ERROR)
00240                 {
00241                         UERROR("Z_DATA_ERROR : The compressed data (referenced by source) was corrupted.");
00242                 }
00243         }
00244         return data;
00245 }
00246 
00247 } /* namespace rtabmap */


rtabmap
Author(s): Mathieu Labbe
autogenerated on Fri Aug 28 2015 12:51:31