codec.cpp
Go to the documentation of this file.
00001 /*********************************************************************
00002 * Software License Agreement (BSD License)
00003 *
00004 *  Copyright (c) 2012 Willow Garage.
00005 *  Copyright (c) 2016 Google, Inc.
00006 *  All rights reserved.
00007 *
00008 *  Redistribution and use in source and binary forms, with or without
00009 *  modification, are permitted provided that the following conditions
00010 *  are met:
00011 *
00012 *   * Redistributions of source code must retain the above copyright
00013 *     notice, this list of conditions and the following disclaimer.
00014 *   * Redistributions in binary form must reproduce the above
00015 *     copyright notice, this list of conditions and the following
00016 *     disclaimer in the documentation and/or other materials provided
00017 *     with the distribution.
00018 *   * Neither the name of the Willow Garage nor the names of its
00019 *     contributors may be used to endorse or promote products derived
00020 *     from this software without specific prior written permission.
00021 *
00022 *  THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
00023 *  "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
00024 *  LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
00025 *  FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
00026 *  COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
00027 *  INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
00028 *  BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
00029 *  LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
00030 *  CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
00031 *  LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
00032 *  ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
00033 *  POSSIBILITY OF SUCH DAMAGE.
00034 *********************************************************************/
00035 
00036 #include <limits>
00037 #include <string>
00038 #include <vector>
00039 
00040 #include <opencv2/highgui/highgui.hpp>
00041 
00042 #include "cv_bridge/cv_bridge.h"
00043 #include "compressed_depth_image_transport/codec.h"
00044 #include "compressed_depth_image_transport/compression_common.h"
00045 #include "ros/ros.h"
00046 
00047 // If OpenCV3
00048 #ifndef CV_VERSION_EPOCH
00049 #include <opencv2/imgcodecs.hpp>
00050 
00051 // If OpenCV4
00052 #if CV_VERSION_MAJOR > 3
00053 #include <opencv2/imgcodecs/legacy/constants_c.h>
00054 #endif
00055 #endif
00056 
00057 namespace enc = sensor_msgs::image_encodings;
00058 using namespace cv;
00059 
00060 // Encoding and decoding of compressed depth images.
00061 namespace compressed_depth_image_transport
00062 {
00063 
00064 sensor_msgs::Image::Ptr decodeCompressedDepthImage(const sensor_msgs::CompressedImage& message)
00065 {
00066 
00067   cv_bridge::CvImagePtr cv_ptr(new cv_bridge::CvImage);
00068 
00069   // Copy message header
00070   cv_ptr->header = message.header;
00071 
00072   // Assign image encoding
00073   std::string image_encoding = message.format.substr(0, message.format.find(';'));
00074   cv_ptr->encoding = image_encoding;
00075 
00076   // Decode message data
00077   if (message.data.size() > sizeof(ConfigHeader))
00078   {
00079 
00080     // Read compression type from stream
00081     ConfigHeader compressionConfig;
00082     memcpy(&compressionConfig, &message.data[0], sizeof(compressionConfig));
00083 
00084     // Get compressed image data
00085     const std::vector<uint8_t> imageData(message.data.begin() + sizeof(compressionConfig), message.data.end());
00086 
00087     // Depth map decoding
00088     float depthQuantA, depthQuantB;
00089 
00090     // Read quantization parameters
00091     depthQuantA = compressionConfig.depthParam[0];
00092     depthQuantB = compressionConfig.depthParam[1];
00093 
00094     if (enc::bitDepth(image_encoding) == 32)
00095     {
00096       cv::Mat decompressed;
00097       try
00098       {
00099         // Decode image data
00100         decompressed = cv::imdecode(imageData, cv::IMREAD_UNCHANGED);
00101       }
00102       catch (cv::Exception& e)
00103       {
00104         ROS_ERROR("%s", e.what());
00105         return sensor_msgs::Image::Ptr();
00106       }
00107 
00108       size_t rows = decompressed.rows;
00109       size_t cols = decompressed.cols;
00110 
00111       if ((rows > 0) && (cols > 0))
00112       {
00113         cv_ptr->image = Mat(rows, cols, CV_32FC1);
00114 
00115         // Depth conversion
00116         MatIterator_<float> itDepthImg = cv_ptr->image.begin<float>(),
00117                             itDepthImg_end = cv_ptr->image.end<float>();
00118         MatConstIterator_<unsigned short> itInvDepthImg = decompressed.begin<unsigned short>(),
00119                                           itInvDepthImg_end = decompressed.end<unsigned short>();
00120 
00121         for (; (itDepthImg != itDepthImg_end) && (itInvDepthImg != itInvDepthImg_end); ++itDepthImg, ++itInvDepthImg)
00122         {
00123           // check for NaN & max depth
00124           if (*itInvDepthImg)
00125           {
00126             *itDepthImg = depthQuantA / ((float)*itInvDepthImg - depthQuantB);
00127           }
00128           else
00129           {
00130             *itDepthImg = std::numeric_limits<float>::quiet_NaN();
00131           }
00132         }
00133 
00134         // Publish message to user callback
00135         return cv_ptr->toImageMsg();
00136       }
00137     }
00138     else
00139     {
00140       // Decode raw image
00141       try
00142       {
00143         cv_ptr->image = cv::imdecode(imageData, CV_LOAD_IMAGE_UNCHANGED);
00144       }
00145       catch (cv::Exception& e)
00146       {
00147         ROS_ERROR("%s", e.what());
00148         return sensor_msgs::Image::Ptr();
00149       }
00150 
00151       size_t rows = cv_ptr->image.rows;
00152       size_t cols = cv_ptr->image.cols;
00153 
00154       if ((rows > 0) && (cols > 0))
00155       {
00156         // Publish message to user callback
00157         return cv_ptr->toImageMsg();
00158       }
00159     }
00160   }
00161   return sensor_msgs::Image::Ptr();
00162 }
00163 
00164 sensor_msgs::CompressedImage::Ptr encodeCompressedDepthImage(
00165     const sensor_msgs::Image& message,
00166     double depth_max, double depth_quantization, int png_level)
00167 {
00168 
00169   // Compressed image message
00170   sensor_msgs::CompressedImage::Ptr compressed(new sensor_msgs::CompressedImage());
00171   compressed->header = message.header;
00172   compressed->format = message.encoding;
00173 
00174   // Compression settings
00175   std::vector<int> params;
00176   params.resize(3, 0);
00177 
00178   // Bit depth of image encoding
00179   int bitDepth = enc::bitDepth(message.encoding);
00180   int numChannels = enc::numChannels(message.encoding);
00181 
00182   // Image compression configuration
00183   ConfigHeader compressionConfig;
00184   compressionConfig.format = INV_DEPTH;
00185 
00186   // Compressed image data
00187   std::vector<uint8_t> compressedImage;
00188 
00189   // Update ros message format header
00190   compressed->format += "; compressedDepth";
00191 
00192   // Check input format
00193   params[0] = cv::IMWRITE_PNG_COMPRESSION;
00194   params[1] = png_level;
00195 
00196   if ((bitDepth == 32) && (numChannels == 1))
00197   {
00198     float depthZ0 = depth_quantization;
00199     float depthMax = depth_max;
00200 
00201     // OpenCV-ROS bridge
00202     cv_bridge::CvImagePtr cv_ptr;
00203     try
00204     {
00205       cv_ptr = cv_bridge::toCvCopy(message);
00206     }
00207     catch (cv_bridge::Exception& e)
00208     {
00209       ROS_ERROR("%s", e.what());
00210       return sensor_msgs::CompressedImage::Ptr();
00211     }
00212 
00213     const Mat& depthImg = cv_ptr->image;
00214     size_t rows = depthImg.rows;
00215     size_t cols = depthImg.cols;
00216 
00217     if ((rows > 0) && (cols > 0))
00218     {
00219       // Allocate matrix for inverse depth (disparity) coding
00220       Mat invDepthImg(rows, cols, CV_16UC1);
00221 
00222       // Inverse depth quantization parameters
00223       float depthQuantA = depthZ0 * (depthZ0 + 1.0f);
00224       float depthQuantB = 1.0f - depthQuantA / depthMax;
00225 
00226       // Matrix iterators
00227       MatConstIterator_<float> itDepthImg = depthImg.begin<float>(),
00228                                itDepthImg_end = depthImg.end<float>();
00229       MatIterator_<unsigned short> itInvDepthImg = invDepthImg.begin<unsigned short>(),
00230                                    itInvDepthImg_end = invDepthImg.end<unsigned short>();
00231 
00232       // Quantization
00233       for (; (itDepthImg != itDepthImg_end) && (itInvDepthImg != itInvDepthImg_end); ++itDepthImg, ++itInvDepthImg)
00234       {
00235         // check for NaN & max depth
00236         if (*itDepthImg < depthMax)
00237         {
00238           *itInvDepthImg = depthQuantA / *itDepthImg + depthQuantB;
00239         }
00240         else
00241         {
00242           *itInvDepthImg = 0;
00243         }
00244       }
00245 
00246       // Add coding parameters to header
00247       compressionConfig.depthParam[0] = depthQuantA;
00248       compressionConfig.depthParam[1] = depthQuantB;
00249 
00250       try
00251       {
00252         // Compress quantized disparity image
00253         if (cv::imencode(".png", invDepthImg, compressedImage, params))
00254         {
00255           float cRatio = (float)(cv_ptr->image.rows * cv_ptr->image.cols * cv_ptr->image.elemSize())
00256               / (float)compressedImage.size();
00257           ROS_DEBUG("Compressed Depth Image Transport - Compression: 1:%.2f (%lu bytes)", cRatio, compressedImage.size());
00258         }
00259         else
00260         {
00261           ROS_ERROR("cv::imencode (png) failed on input image");
00262           return sensor_msgs::CompressedImage::Ptr();
00263         }
00264       }
00265       catch (cv::Exception& e)
00266       {
00267         ROS_ERROR("%s", e.msg.c_str());
00268         return sensor_msgs::CompressedImage::Ptr();
00269       }
00270     }
00271   }
00272   // Raw depth map compression
00273   else if ((bitDepth == 16) && (numChannels == 1))
00274   {
00275     // OpenCV-ROS bridge
00276     cv_bridge::CvImagePtr cv_ptr;
00277     try
00278     {
00279       cv_ptr = cv_bridge::toCvCopy(message);
00280     }
00281     catch (Exception& e)
00282     {
00283       ROS_ERROR("%s", e.msg.c_str());
00284       return sensor_msgs::CompressedImage::Ptr();
00285     }
00286 
00287     const Mat& depthImg = cv_ptr->image;
00288     size_t rows = depthImg.rows;
00289     size_t cols = depthImg.cols;
00290 
00291     if ((rows > 0) && (cols > 0))
00292     {
00293       unsigned short depthMaxUShort = static_cast<unsigned short>(depth_max * 1000.0f);
00294 
00295       // Matrix iterators
00296       MatIterator_<unsigned short> itDepthImg = cv_ptr->image.begin<unsigned short>(),
00297                                     itDepthImg_end = cv_ptr->image.end<unsigned short>();
00298 
00299       // Max depth filter
00300       for (; itDepthImg != itDepthImg_end; ++itDepthImg)
00301       {
00302         if (*itDepthImg > depthMaxUShort)
00303           *itDepthImg = 0;
00304       }
00305 
00306       // Compress raw depth image
00307       if (cv::imencode(".png", cv_ptr->image, compressedImage, params))
00308       {
00309         float cRatio = (float)(cv_ptr->image.rows * cv_ptr->image.cols * cv_ptr->image.elemSize())
00310             / (float)compressedImage.size();
00311         ROS_DEBUG("Compressed Depth Image Transport - Compression: 1:%.2f (%lu bytes)", cRatio, compressedImage.size());
00312       }
00313       else
00314       {
00315         ROS_ERROR("cv::imencode (png) failed on input image");
00316         return sensor_msgs::CompressedImage::Ptr();
00317       }
00318     }
00319   }
00320   else
00321   {
00322     ROS_ERROR("Compressed Depth Image Transport - Compression requires single-channel 32bit-floating point or 16bit raw depth images (input format is: %s).", message.encoding.c_str());
00323     return sensor_msgs::CompressedImage::Ptr();
00324   }
00325 
00326   if (compressedImage.size() > 0)
00327   {
00328     // Add configuration to binary output
00329     compressed->data.resize(sizeof(ConfigHeader));
00330     memcpy(&compressed->data[0], &compressionConfig, sizeof(ConfigHeader));
00331 
00332     // Add compressed binary data to messages
00333     compressed->data.insert(compressed->data.end(), compressedImage.begin(), compressedImage.end());
00334 
00335     return compressed;
00336   }
00337 
00338   return sensor_msgs::CompressedImage::Ptr();
00339 }
00340 
00341 }  // namespace compressed_depth_image_transport


compressed_depth_image_transport
Author(s): Julius Kammerl
autogenerated on Tue Jul 2 2019 19:53:20