Go to the documentation of this file.00001
00002
00003
00004
00005
00006
00007
00008
00009
00010
00011
00012
00013
00014
00015
00016
00017
00018
00019
00020
00021
00022
00023
00024
00025
00026
00027
00028
00029
00030
00031
00032
00033
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
00048 #ifndef CV_VERSION_EPOCH
00049 #include <opencv2/imgcodecs.hpp>
00050
00051
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
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
00070 cv_ptr->header = message.header;
00071
00072
00073 std::string image_encoding = message.format.substr(0, message.format.find(';'));
00074 cv_ptr->encoding = image_encoding;
00075
00076
00077 if (message.data.size() > sizeof(ConfigHeader))
00078 {
00079
00080
00081 ConfigHeader compressionConfig;
00082 memcpy(&compressionConfig, &message.data[0], sizeof(compressionConfig));
00083
00084
00085 const std::vector<uint8_t> imageData(message.data.begin() + sizeof(compressionConfig), message.data.end());
00086
00087
00088 float depthQuantA, depthQuantB;
00089
00090
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
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
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
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
00135 return cv_ptr->toImageMsg();
00136 }
00137 }
00138 else
00139 {
00140
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
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
00170 sensor_msgs::CompressedImage::Ptr compressed(new sensor_msgs::CompressedImage());
00171 compressed->header = message.header;
00172 compressed->format = message.encoding;
00173
00174
00175 std::vector<int> params;
00176 params.resize(3, 0);
00177
00178
00179 int bitDepth = enc::bitDepth(message.encoding);
00180 int numChannels = enc::numChannels(message.encoding);
00181
00182
00183 ConfigHeader compressionConfig;
00184 compressionConfig.format = INV_DEPTH;
00185
00186
00187 std::vector<uint8_t> compressedImage;
00188
00189
00190 compressed->format += "; compressedDepth";
00191
00192
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
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
00220 Mat invDepthImg(rows, cols, CV_16UC1);
00221
00222
00223 float depthQuantA = depthZ0 * (depthZ0 + 1.0f);
00224 float depthQuantB = 1.0f - depthQuantA / depthMax;
00225
00226
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
00233 for (; (itDepthImg != itDepthImg_end) && (itInvDepthImg != itInvDepthImg_end); ++itDepthImg, ++itInvDepthImg)
00234 {
00235
00236 if (*itDepthImg < depthMax)
00237 {
00238 *itInvDepthImg = depthQuantA / *itDepthImg + depthQuantB;
00239 }
00240 else
00241 {
00242 *itInvDepthImg = 0;
00243 }
00244 }
00245
00246
00247 compressionConfig.depthParam[0] = depthQuantA;
00248 compressionConfig.depthParam[1] = depthQuantB;
00249
00250 try
00251 {
00252
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
00273 else if ((bitDepth == 16) && (numChannels == 1))
00274 {
00275
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
00296 MatIterator_<unsigned short> itDepthImg = cv_ptr->image.begin<unsigned short>(),
00297 itDepthImg_end = cv_ptr->image.end<unsigned short>();
00298
00299
00300 for (; itDepthImg != itDepthImg_end; ++itDepthImg)
00301 {
00302 if (*itDepthImg > depthMaxUShort)
00303 *itDepthImg = 0;
00304 }
00305
00306
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
00329 compressed->data.resize(sizeof(ConfigHeader));
00330 memcpy(&compressed->data[0], &compressionConfig, sizeof(ConfigHeader));
00331
00332
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 }