codec.cpp
Go to the documentation of this file.
1 /*********************************************************************
2 * Software License Agreement (BSD License)
3 *
4 * Copyright (c) 2012 Willow Garage.
5 * Copyright (c) 2016 Google, Inc.
6 * All rights reserved.
7 *
8 * Redistribution and use in source and binary forms, with or without
9 * modification, are permitted provided that the following conditions
10 * are met:
11 *
12 * * Redistributions of source code must retain the above copyright
13 * notice, this list of conditions and the following disclaimer.
14 * * Redistributions in binary form must reproduce the above
15 * copyright notice, this list of conditions and the following
16 * disclaimer in the documentation and/or other materials provided
17 * with the distribution.
18 * * Neither the name of the Willow Garage nor the names of its
19 * contributors may be used to endorse or promote products derived
20 * from this software without specific prior written permission.
21 *
22 * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
23 * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
24 * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
25 * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
26 * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
27 * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
28 * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
29 * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
30 * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
31 * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
32 * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
33 * POSSIBILITY OF SUCH DAMAGE.
34 *********************************************************************/
35 
36 #include <limits>
37 #include <string>
38 #include <vector>
39 
40 #include <opencv2/highgui/highgui.hpp>
41 
42 #include "cv_bridge/cv_bridge.h"
46 #include "ros/ros.h"
47 
48 // If OpenCV3
49 #ifndef CV_VERSION_EPOCH
50 #include <opencv2/imgcodecs.hpp>
51 
52 // If OpenCV4
53 #if CV_VERSION_MAJOR > 3
54 #include <opencv2/imgcodecs/legacy/constants_c.h>
55 #endif
56 #endif
57 
59 using namespace cv;
60 
61 // Encoding and decoding of compressed depth images.
63 {
64 
65 sensor_msgs::Image::Ptr decodeCompressedDepthImage(const sensor_msgs::CompressedImage& message)
66 {
68 
69  // Copy message header
70  cv_ptr->header = message.header;
71 
72  // Assign image encoding
73  const size_t split_pos = message.format.find(';');
74  const std::string image_encoding = message.format.substr(0, split_pos);
75  std::string compression_format;
76  // Older version of compressed_depth_image_transport supports only png.
77  if (split_pos == std::string::npos) {
78  compression_format = "png";
79  } else {
80  std::string format = message.format.substr(split_pos);
81  if (format.find("compressedDepth png") != std::string::npos) {
82  compression_format = "png";
83  } else if (format.find("compressedDepth rvl") != std::string::npos) {
84  compression_format = "rvl";
85  } else {
86  ROS_ERROR("Unsupported image format: %s", message.format.c_str());
87  return sensor_msgs::Image::Ptr();
88  }
89  }
90 
91  cv_ptr->encoding = image_encoding;
92 
93  // Decode message data
94  if (message.data.size() > sizeof(ConfigHeader))
95  {
96 
97  // Read compression type from stream
98  ConfigHeader compressionConfig;
99  memcpy(&compressionConfig, &message.data[0], sizeof(compressionConfig));
100 
101  // Get compressed image data
102  const std::vector<uint8_t> imageData(message.data.begin() + sizeof(compressionConfig), message.data.end());
103 
104  // Depth map decoding
105  float depthQuantA, depthQuantB;
106 
107  // Read quantization parameters
108  depthQuantA = compressionConfig.depthParam[0];
109  depthQuantB = compressionConfig.depthParam[1];
110 
111  if (enc::bitDepth(image_encoding) == 32)
112  {
113  cv::Mat decompressed;
114  if (compression_format == "png") {
115  try
116  {
117  // Decode image data
118  decompressed = cv::imdecode(imageData, cv::IMREAD_UNCHANGED);
119  }
120  catch (cv::Exception& e)
121  {
122  ROS_ERROR("%s", e.what());
123  return sensor_msgs::Image::Ptr();
124  }
125  } else if (compression_format == "rvl") {
126  const unsigned char *buffer = imageData.data();
127  uint32_t cols, rows;
128  memcpy(&cols, &buffer[0], 4);
129  memcpy(&rows, &buffer[4], 4);
130  decompressed = Mat(rows, cols, CV_16UC1);
131  RvlCodec rvl;
132  rvl.DecompressRVL(&buffer[8], decompressed.ptr<unsigned short>(), cols * rows);
133  } else {
134  return sensor_msgs::Image::Ptr();
135  }
136 
137  size_t rows = decompressed.rows;
138  size_t cols = decompressed.cols;
139 
140  if ((rows > 0) && (cols > 0))
141  {
142  cv_ptr->image = Mat(rows, cols, CV_32FC1);
143 
144  // Depth conversion
145  MatIterator_<float> itDepthImg = cv_ptr->image.begin<float>(),
146  itDepthImg_end = cv_ptr->image.end<float>();
147  MatConstIterator_<unsigned short> itInvDepthImg = decompressed.begin<unsigned short>(),
148  itInvDepthImg_end = decompressed.end<unsigned short>();
149 
150  for (; (itDepthImg != itDepthImg_end) && (itInvDepthImg != itInvDepthImg_end); ++itDepthImg, ++itInvDepthImg)
151  {
152  // check for NaN & max depth
153  if (*itInvDepthImg)
154  {
155  *itDepthImg = depthQuantA / ((float)*itInvDepthImg - depthQuantB);
156  }
157  else
158  {
159  *itDepthImg = std::numeric_limits<float>::quiet_NaN();
160  }
161  }
162 
163  // Publish message to user callback
164  return cv_ptr->toImageMsg();
165  }
166  }
167  else
168  {
169  // Decode raw image
170  if (compression_format == "png") {
171  try
172  {
173  cv_ptr->image = cv::imdecode(imageData, CV_LOAD_IMAGE_UNCHANGED);
174  }
175  catch (cv::Exception& e)
176  {
177  ROS_ERROR("%s", e.what());
178  return sensor_msgs::Image::Ptr();
179  }
180  } else if (compression_format == "rvl") {
181  const unsigned char *buffer = imageData.data();
182  uint32_t cols, rows;
183  memcpy(&cols, &buffer[0], 4);
184  memcpy(&rows, &buffer[4], 4);
185  cv_ptr->image = Mat(rows, cols, CV_16UC1);
186  RvlCodec rvl;
187  rvl.DecompressRVL(&buffer[8], cv_ptr->image.ptr<unsigned short>(), cols * rows);
188  } else {
189  return sensor_msgs::Image::Ptr();
190  }
191 
192  size_t rows = cv_ptr->image.rows;
193  size_t cols = cv_ptr->image.cols;
194 
195  if ((rows > 0) && (cols > 0))
196  {
197  // Publish message to user callback
198  return cv_ptr->toImageMsg();
199  }
200  }
201  }
202  return sensor_msgs::Image::Ptr();
203 }
204 
205 sensor_msgs::CompressedImage::Ptr encodeCompressedDepthImage(
206  const sensor_msgs::Image& message,
207  const std::string& compression_format,
208  double depth_max, double depth_quantization, int png_level)
209 {
210 
211  // Compressed image message
212  sensor_msgs::CompressedImage::Ptr compressed(new sensor_msgs::CompressedImage());
213  compressed->header = message.header;
214  compressed->format = message.encoding;
215 
216  // Compression settings
217  std::vector<int> params;
218  params.resize(3, 0);
219 
220  // Bit depth of image encoding
221  int bitDepth = enc::bitDepth(message.encoding);
222  int numChannels = enc::numChannels(message.encoding);
223 
224  // Image compression configuration
225  ConfigHeader compressionConfig;
226  compressionConfig.format = INV_DEPTH;
227 
228  // Compressed image data
229  std::vector<uint8_t> compressedImage;
230 
231  // Update ros message format header
232  compressed->format += "; compressedDepth " + compression_format;
233 
234  // Check input format
235  params[0] = cv::IMWRITE_PNG_COMPRESSION;
236  params[1] = png_level;
237 
238  if ((bitDepth == 32) && (numChannels == 1))
239  {
240  float depthZ0 = depth_quantization;
241  float depthMax = depth_max;
242 
243  // OpenCV-ROS bridge
244  cv_bridge::CvImagePtr cv_ptr;
245  try
246  {
247  cv_ptr = cv_bridge::toCvCopy(message);
248  }
249  catch (cv_bridge::Exception& e)
250  {
251  ROS_ERROR("%s", e.what());
252  return sensor_msgs::CompressedImage::Ptr();
253  }
254 
255  const Mat& depthImg = cv_ptr->image;
256  size_t rows = depthImg.rows;
257  size_t cols = depthImg.cols;
258 
259  if ((rows > 0) && (cols > 0))
260  {
261  // Allocate matrix for inverse depth (disparity) coding
262  Mat invDepthImg(rows, cols, CV_16UC1);
263 
264  // Inverse depth quantization parameters
265  float depthQuantA = depthZ0 * (depthZ0 + 1.0f);
266  float depthQuantB = 1.0f - depthQuantA / depthMax;
267 
268  // Matrix iterators
269  MatConstIterator_<float> itDepthImg = depthImg.begin<float>(),
270  itDepthImg_end = depthImg.end<float>();
271  MatIterator_<unsigned short> itInvDepthImg = invDepthImg.begin<unsigned short>(),
272  itInvDepthImg_end = invDepthImg.end<unsigned short>();
273 
274  // Quantization
275  for (; (itDepthImg != itDepthImg_end) && (itInvDepthImg != itInvDepthImg_end); ++itDepthImg, ++itInvDepthImg)
276  {
277  // check for NaN & max depth
278  if (*itDepthImg < depthMax)
279  {
280  *itInvDepthImg = depthQuantA / *itDepthImg + depthQuantB;
281  }
282  else
283  {
284  *itInvDepthImg = 0;
285  }
286  }
287 
288  // Add coding parameters to header
289  compressionConfig.depthParam[0] = depthQuantA;
290  compressionConfig.depthParam[1] = depthQuantB;
291 
292  // Compress quantized disparity image
293  if (compression_format == "png") {
294  try
295  {
296  if (cv::imencode(".png", invDepthImg, compressedImage, params))
297  {
298  float cRatio = (float)(cv_ptr->image.rows * cv_ptr->image.cols * cv_ptr->image.elemSize())
299  / (float)compressedImage.size();
300  ROS_DEBUG("Compressed Depth Image Transport - Compression: 1:%.2f (%lu bytes)", cRatio, compressedImage.size());
301  }
302  else
303  {
304  ROS_ERROR("cv::imencode (png) failed on input image");
305  return sensor_msgs::CompressedImage::Ptr();
306  }
307  }
308  catch (cv::Exception& e)
309  {
310  ROS_ERROR("%s", e.msg.c_str());
311  return sensor_msgs::CompressedImage::Ptr();
312  }
313  } else if (compression_format == "rvl") {
314  int numPixels = invDepthImg.rows * invDepthImg.cols;
315  // In the worst case, RVL compression results in ~1.5x larger data.
316  compressedImage.resize(3 * numPixels + 12);
317  uint32_t cols = invDepthImg.cols;
318  uint32_t rows = invDepthImg.rows;
319  memcpy(&compressedImage[0], &cols, 4);
320  memcpy(&compressedImage[4], &rows, 4);
321  RvlCodec rvl;
322  int compressedSize = rvl.CompressRVL(invDepthImg.ptr<unsigned short>(), &compressedImage[8], numPixels);
323  compressedImage.resize(8 + compressedSize);
324  }
325  }
326  }
327  // Raw depth map compression
328  else if ((bitDepth == 16) && (numChannels == 1))
329  {
330  // OpenCV-ROS bridge
331  cv_bridge::CvImagePtr cv_ptr;
332  try
333  {
334  cv_ptr = cv_bridge::toCvCopy(message);
335  }
336  catch (Exception& e)
337  {
338  ROS_ERROR("%s", e.msg.c_str());
339  return sensor_msgs::CompressedImage::Ptr();
340  }
341 
342  const Mat& depthImg = cv_ptr->image;
343  size_t rows = depthImg.rows;
344  size_t cols = depthImg.cols;
345 
346  if ((rows > 0) && (cols > 0))
347  {
348  unsigned short depthMaxUShort = static_cast<unsigned short>(depth_max * 1000.0f);
349 
350  // Matrix iterators
351  MatIterator_<unsigned short> itDepthImg = cv_ptr->image.begin<unsigned short>(),
352  itDepthImg_end = cv_ptr->image.end<unsigned short>();
353 
354  // Max depth filter
355  for (; itDepthImg != itDepthImg_end; ++itDepthImg)
356  {
357  if (*itDepthImg > depthMaxUShort)
358  *itDepthImg = 0;
359  }
360 
361  // Compress raw depth image
362  if (compression_format == "png") {
363  if (cv::imencode(".png", cv_ptr->image, compressedImage, params))
364  {
365  float cRatio = (float)(cv_ptr->image.rows * cv_ptr->image.cols * cv_ptr->image.elemSize())
366  / (float)compressedImage.size();
367  ROS_DEBUG("Compressed Depth Image Transport - Compression: 1:%.2f (%lu bytes)", cRatio, compressedImage.size());
368  }
369  else
370  {
371  ROS_ERROR("cv::imencode (png) failed on input image");
372  return sensor_msgs::CompressedImage::Ptr();
373  }
374  } else if (compression_format == "rvl") {
375  int numPixels = cv_ptr->image.rows * cv_ptr->image.cols;
376  // In the worst case, RVL compression results in ~1.5x larger data.
377  compressedImage.resize(3 * numPixels + 12);
378  uint32_t cols = cv_ptr->image.cols;
379  uint32_t rows = cv_ptr->image.rows;
380  memcpy(&compressedImage[0], &cols, 4);
381  memcpy(&compressedImage[4], &rows, 4);
382  RvlCodec rvl;
383  int compressedSize = rvl.CompressRVL(cv_ptr->image.ptr<unsigned short>(), &compressedImage[8], numPixels);
384  compressedImage.resize(8 + compressedSize);
385  }
386  }
387  }
388  else
389  {
390  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());
391  return sensor_msgs::CompressedImage::Ptr();
392  }
393 
394  if (compressedImage.size() > 0)
395  {
396  // Add configuration to binary output
397  compressed->data.resize(sizeof(ConfigHeader));
398  memcpy(&compressed->data[0], &compressionConfig, sizeof(ConfigHeader));
399 
400  // Add compressed binary data to messages
401  compressed->data.insert(compressed->data.end(), compressedImage.begin(), compressedImage.end());
402 
403  return compressed;
404  }
405 
406  return sensor_msgs::CompressedImage::Ptr();
407 }
408 
409 } // namespace compressed_depth_image_transport
sensor_msgs::Image::Ptr decodeCompressedDepthImage(const sensor_msgs::CompressedImage &compressed_image)
Definition: codec.cpp:65
sensor_msgs::CompressedImage::Ptr encodeCompressedDepthImage(const sensor_msgs::Image &message, const std::string &compression_format, double depth_max, double depth_quantization, int png_level)
Definition: codec.cpp:205
CvImagePtr toCvCopy(const sensor_msgs::ImageConstPtr &source, const std::string &encoding=std::string())
#define ROS_ERROR(...)
void DecompressRVL(const unsigned char *input, unsigned short *output, int numPixels)
Definition: rvl_codec.cpp:70
#define ROS_DEBUG(...)
int CompressRVL(const unsigned short *input, unsigned char *output, int numPixels)
Definition: rvl_codec.cpp:43


compressed_depth_image_transport
Author(s): Julius Kammerl
autogenerated on Fri Sep 20 2019 03:32:12