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 #endif
00051
00052 namespace enc = sensor_msgs::image_encodings;
00053 using namespace cv;
00054
00055
00056 namespace compressed_depth_image_transport
00057 {
00058
00059 sensor_msgs::Image::Ptr decodeCompressedDepthImage(const sensor_msgs::CompressedImage& message)
00060 {
00061
00062 cv_bridge::CvImagePtr cv_ptr(new cv_bridge::CvImage);
00063
00064
00065 cv_ptr->header = message.header;
00066
00067
00068 std::string image_encoding = message.format.substr(0, message.format.find(';'));
00069 cv_ptr->encoding = image_encoding;
00070
00071
00072 if (message.data.size() > sizeof(ConfigHeader))
00073 {
00074
00075
00076 ConfigHeader compressionConfig;
00077 memcpy(&compressionConfig, &message.data[0], sizeof(compressionConfig));
00078
00079
00080 const std::vector<uint8_t> imageData(message.data.begin() + sizeof(compressionConfig), message.data.end());
00081
00082
00083 float depthQuantA, depthQuantB;
00084
00085
00086 depthQuantA = compressionConfig.depthParam[0];
00087 depthQuantB = compressionConfig.depthParam[1];
00088
00089 if (enc::bitDepth(image_encoding) == 32)
00090 {
00091 cv::Mat decompressed;
00092 try
00093 {
00094
00095 decompressed = cv::imdecode(imageData, cv::IMREAD_UNCHANGED);
00096 }
00097 catch (cv::Exception& e)
00098 {
00099 ROS_ERROR("%s", e.what());
00100 return sensor_msgs::Image::Ptr();
00101 }
00102
00103 size_t rows = decompressed.rows;
00104 size_t cols = decompressed.cols;
00105
00106 if ((rows > 0) && (cols > 0))
00107 {
00108 cv_ptr->image = Mat(rows, cols, CV_32FC1);
00109
00110
00111 MatIterator_<float> itDepthImg = cv_ptr->image.begin<float>(),
00112 itDepthImg_end = cv_ptr->image.end<float>();
00113 MatConstIterator_<unsigned short> itInvDepthImg = decompressed.begin<unsigned short>(),
00114 itInvDepthImg_end = decompressed.end<unsigned short>();
00115
00116 for (; (itDepthImg != itDepthImg_end) && (itInvDepthImg != itInvDepthImg_end); ++itDepthImg, ++itInvDepthImg)
00117 {
00118
00119 if (*itInvDepthImg)
00120 {
00121 *itDepthImg = depthQuantA / ((float)*itInvDepthImg - depthQuantB);
00122 }
00123 else
00124 {
00125 *itDepthImg = std::numeric_limits<float>::quiet_NaN();
00126 }
00127 }
00128
00129
00130 return cv_ptr->toImageMsg();
00131 }
00132 }
00133 else
00134 {
00135
00136 try
00137 {
00138 cv_ptr->image = cv::imdecode(imageData, CV_LOAD_IMAGE_UNCHANGED);
00139 }
00140 catch (cv::Exception& e)
00141 {
00142 ROS_ERROR("%s", e.what());
00143 return sensor_msgs::Image::Ptr();
00144 }
00145
00146 size_t rows = cv_ptr->image.rows;
00147 size_t cols = cv_ptr->image.cols;
00148
00149 if ((rows > 0) && (cols > 0))
00150 {
00151
00152 return cv_ptr->toImageMsg();
00153 }
00154 }
00155 }
00156 return sensor_msgs::Image::Ptr();
00157 }
00158
00159 sensor_msgs::CompressedImage::Ptr encodeCompressedDepthImage(
00160 const sensor_msgs::Image& message,
00161 double depth_max, double depth_quantization, int png_level)
00162 {
00163
00164
00165 sensor_msgs::CompressedImage::Ptr compressed(new sensor_msgs::CompressedImage());
00166 compressed->header = message.header;
00167 compressed->format = message.encoding;
00168
00169
00170 std::vector<int> params;
00171 params.resize(3, 0);
00172
00173
00174 int bitDepth = enc::bitDepth(message.encoding);
00175 int numChannels = enc::numChannels(message.encoding);
00176
00177
00178 ConfigHeader compressionConfig;
00179 compressionConfig.format = INV_DEPTH;
00180
00181
00182 std::vector<uint8_t> compressedImage;
00183
00184
00185 compressed->format += "; compressedDepth";
00186
00187
00188 params[0] = cv::IMWRITE_PNG_COMPRESSION;
00189 params[1] = png_level;
00190
00191 if ((bitDepth == 32) && (numChannels == 1))
00192 {
00193 float depthZ0 = depth_quantization;
00194 float depthMax = depth_max;
00195
00196
00197 cv_bridge::CvImagePtr cv_ptr;
00198 try
00199 {
00200 cv_ptr = cv_bridge::toCvCopy(message);
00201 }
00202 catch (cv_bridge::Exception& e)
00203 {
00204 ROS_ERROR("%s", e.what());
00205 return sensor_msgs::CompressedImage::Ptr();
00206 }
00207
00208 const Mat& depthImg = cv_ptr->image;
00209 size_t rows = depthImg.rows;
00210 size_t cols = depthImg.cols;
00211
00212 if ((rows > 0) && (cols > 0))
00213 {
00214
00215 Mat invDepthImg(rows, cols, CV_16UC1);
00216
00217
00218 float depthQuantA = depthZ0 * (depthZ0 + 1.0f);
00219 float depthQuantB = 1.0f - depthQuantA / depthMax;
00220
00221
00222 MatConstIterator_<float> itDepthImg = depthImg.begin<float>(),
00223 itDepthImg_end = depthImg.end<float>();
00224 MatIterator_<unsigned short> itInvDepthImg = invDepthImg.begin<unsigned short>(),
00225 itInvDepthImg_end = invDepthImg.end<unsigned short>();
00226
00227
00228 for (; (itDepthImg != itDepthImg_end) && (itInvDepthImg != itInvDepthImg_end); ++itDepthImg, ++itInvDepthImg)
00229 {
00230
00231 if (*itDepthImg < depthMax)
00232 {
00233 *itInvDepthImg = depthQuantA / *itDepthImg + depthQuantB;
00234 }
00235 else
00236 {
00237 *itInvDepthImg = 0;
00238 }
00239 }
00240
00241
00242 compressionConfig.depthParam[0] = depthQuantA;
00243 compressionConfig.depthParam[1] = depthQuantB;
00244
00245 try
00246 {
00247
00248 if (cv::imencode(".png", invDepthImg, compressedImage, params))
00249 {
00250 float cRatio = (float)(cv_ptr->image.rows * cv_ptr->image.cols * cv_ptr->image.elemSize())
00251 / (float)compressedImage.size();
00252 ROS_DEBUG("Compressed Depth Image Transport - Compression: 1:%.2f (%lu bytes)", cRatio, compressedImage.size());
00253 }
00254 else
00255 {
00256 ROS_ERROR("cv::imencode (png) failed on input image");
00257 return sensor_msgs::CompressedImage::Ptr();
00258 }
00259 }
00260 catch (cv::Exception& e)
00261 {
00262 ROS_ERROR("%s", e.msg.c_str());
00263 return sensor_msgs::CompressedImage::Ptr();
00264 }
00265 }
00266 }
00267
00268 else if ((bitDepth == 16) && (numChannels == 1))
00269 {
00270
00271 cv_bridge::CvImagePtr cv_ptr;
00272 try
00273 {
00274 cv_ptr = cv_bridge::toCvCopy(message);
00275 }
00276 catch (Exception& e)
00277 {
00278 ROS_ERROR("%s", e.msg.c_str());
00279 return sensor_msgs::CompressedImage::Ptr();
00280 }
00281
00282 const Mat& depthImg = cv_ptr->image;
00283 size_t rows = depthImg.rows;
00284 size_t cols = depthImg.cols;
00285
00286 if ((rows > 0) && (cols > 0))
00287 {
00288 unsigned short depthMaxUShort = static_cast<unsigned short>(depth_max * 1000.0f);
00289
00290
00291 MatIterator_<unsigned short> itDepthImg = cv_ptr->image.begin<unsigned short>(),
00292 itDepthImg_end = cv_ptr->image.end<unsigned short>();
00293
00294
00295 for (; itDepthImg != itDepthImg_end; ++itDepthImg)
00296 {
00297 if (*itDepthImg > depthMaxUShort)
00298 *itDepthImg = 0;
00299 }
00300
00301
00302 if (cv::imencode(".png", cv_ptr->image, compressedImage, params))
00303 {
00304 float cRatio = (float)(cv_ptr->image.rows * cv_ptr->image.cols * cv_ptr->image.elemSize())
00305 / (float)compressedImage.size();
00306 ROS_DEBUG("Compressed Depth Image Transport - Compression: 1:%.2f (%lu bytes)", cRatio, compressedImage.size());
00307 }
00308 else
00309 {
00310 ROS_ERROR("cv::imencode (png) failed on input image");
00311 return sensor_msgs::CompressedImage::Ptr();
00312 }
00313 }
00314 }
00315 else
00316 {
00317 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());
00318 return sensor_msgs::CompressedImage::Ptr();
00319 }
00320
00321 if (compressedImage.size() > 0)
00322 {
00323
00324 compressed->data.resize(sizeof(ConfigHeader));
00325 memcpy(&compressed->data[0], &compressionConfig, sizeof(ConfigHeader));
00326
00327
00328 compressed->data.insert(compressed->data.end(), compressedImage.begin(), compressedImage.end());
00329
00330 return compressed;
00331 }
00332
00333 return sensor_msgs::CompressedImage::Ptr();
00334 }
00335
00336 }