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"
45 #include "ros/ros.h"
46 
47 // If OpenCV3
48 #ifndef CV_VERSION_EPOCH
49 #include <opencv2/imgcodecs.hpp>
50 
51 // If OpenCV4
52 #if CV_VERSION_MAJOR > 3
53 #include <opencv2/imgcodecs/legacy/constants_c.h>
54 #endif
55 #endif
56 
58 using namespace cv;
59 
60 // Encoding and decoding of compressed depth images.
62 {
63 
64 sensor_msgs::Image::Ptr decodeCompressedDepthImage(const sensor_msgs::CompressedImage& message)
65 {
66 
68 
69  // Copy message header
70  cv_ptr->header = message.header;
71 
72  // Assign image encoding
73  std::string image_encoding = message.format.substr(0, message.format.find(';'));
74  cv_ptr->encoding = image_encoding;
75 
76  // Decode message data
77  if (message.data.size() > sizeof(ConfigHeader))
78  {
79 
80  // Read compression type from stream
81  ConfigHeader compressionConfig;
82  memcpy(&compressionConfig, &message.data[0], sizeof(compressionConfig));
83 
84  // Get compressed image data
85  const std::vector<uint8_t> imageData(message.data.begin() + sizeof(compressionConfig), message.data.end());
86 
87  // Depth map decoding
88  float depthQuantA, depthQuantB;
89 
90  // Read quantization parameters
91  depthQuantA = compressionConfig.depthParam[0];
92  depthQuantB = compressionConfig.depthParam[1];
93 
94  if (enc::bitDepth(image_encoding) == 32)
95  {
96  cv::Mat decompressed;
97  try
98  {
99  // Decode image data
100  decompressed = cv::imdecode(imageData, cv::IMREAD_UNCHANGED);
101  }
102  catch (cv::Exception& e)
103  {
104  ROS_ERROR("%s", e.what());
105  return sensor_msgs::Image::Ptr();
106  }
107 
108  size_t rows = decompressed.rows;
109  size_t cols = decompressed.cols;
110 
111  if ((rows > 0) && (cols > 0))
112  {
113  cv_ptr->image = Mat(rows, cols, CV_32FC1);
114 
115  // Depth conversion
116  MatIterator_<float> itDepthImg = cv_ptr->image.begin<float>(),
117  itDepthImg_end = cv_ptr->image.end<float>();
118  MatConstIterator_<unsigned short> itInvDepthImg = decompressed.begin<unsigned short>(),
119  itInvDepthImg_end = decompressed.end<unsigned short>();
120 
121  for (; (itDepthImg != itDepthImg_end) && (itInvDepthImg != itInvDepthImg_end); ++itDepthImg, ++itInvDepthImg)
122  {
123  // check for NaN & max depth
124  if (*itInvDepthImg)
125  {
126  *itDepthImg = depthQuantA / ((float)*itInvDepthImg - depthQuantB);
127  }
128  else
129  {
130  *itDepthImg = std::numeric_limits<float>::quiet_NaN();
131  }
132  }
133 
134  // Publish message to user callback
135  return cv_ptr->toImageMsg();
136  }
137  }
138  else
139  {
140  // Decode raw image
141  try
142  {
143  cv_ptr->image = cv::imdecode(imageData, CV_LOAD_IMAGE_UNCHANGED);
144  }
145  catch (cv::Exception& e)
146  {
147  ROS_ERROR("%s", e.what());
148  return sensor_msgs::Image::Ptr();
149  }
150 
151  size_t rows = cv_ptr->image.rows;
152  size_t cols = cv_ptr->image.cols;
153 
154  if ((rows > 0) && (cols > 0))
155  {
156  // Publish message to user callback
157  return cv_ptr->toImageMsg();
158  }
159  }
160  }
161  return sensor_msgs::Image::Ptr();
162 }
163 
164 sensor_msgs::CompressedImage::Ptr encodeCompressedDepthImage(
165  const sensor_msgs::Image& message,
166  double depth_max, double depth_quantization, int png_level)
167 {
168 
169  // Compressed image message
170  sensor_msgs::CompressedImage::Ptr compressed(new sensor_msgs::CompressedImage());
171  compressed->header = message.header;
172  compressed->format = message.encoding;
173 
174  // Compression settings
175  std::vector<int> params;
176  params.resize(3, 0);
177 
178  // Bit depth of image encoding
179  int bitDepth = enc::bitDepth(message.encoding);
180  int numChannels = enc::numChannels(message.encoding);
181 
182  // Image compression configuration
183  ConfigHeader compressionConfig;
184  compressionConfig.format = INV_DEPTH;
185 
186  // Compressed image data
187  std::vector<uint8_t> compressedImage;
188 
189  // Update ros message format header
190  compressed->format += "; compressedDepth";
191 
192  // Check input format
193  params[0] = cv::IMWRITE_PNG_COMPRESSION;
194  params[1] = png_level;
195 
196  if ((bitDepth == 32) && (numChannels == 1))
197  {
198  float depthZ0 = depth_quantization;
199  float depthMax = depth_max;
200 
201  // OpenCV-ROS bridge
202  cv_bridge::CvImagePtr cv_ptr;
203  try
204  {
205  cv_ptr = cv_bridge::toCvCopy(message);
206  }
207  catch (cv_bridge::Exception& e)
208  {
209  ROS_ERROR("%s", e.what());
210  return sensor_msgs::CompressedImage::Ptr();
211  }
212 
213  const Mat& depthImg = cv_ptr->image;
214  size_t rows = depthImg.rows;
215  size_t cols = depthImg.cols;
216 
217  if ((rows > 0) && (cols > 0))
218  {
219  // Allocate matrix for inverse depth (disparity) coding
220  Mat invDepthImg(rows, cols, CV_16UC1);
221 
222  // Inverse depth quantization parameters
223  float depthQuantA = depthZ0 * (depthZ0 + 1.0f);
224  float depthQuantB = 1.0f - depthQuantA / depthMax;
225 
226  // Matrix iterators
227  MatConstIterator_<float> itDepthImg = depthImg.begin<float>(),
228  itDepthImg_end = depthImg.end<float>();
229  MatIterator_<unsigned short> itInvDepthImg = invDepthImg.begin<unsigned short>(),
230  itInvDepthImg_end = invDepthImg.end<unsigned short>();
231 
232  // Quantization
233  for (; (itDepthImg != itDepthImg_end) && (itInvDepthImg != itInvDepthImg_end); ++itDepthImg, ++itInvDepthImg)
234  {
235  // check for NaN & max depth
236  if (*itDepthImg < depthMax)
237  {
238  *itInvDepthImg = depthQuantA / *itDepthImg + depthQuantB;
239  }
240  else
241  {
242  *itInvDepthImg = 0;
243  }
244  }
245 
246  // Add coding parameters to header
247  compressionConfig.depthParam[0] = depthQuantA;
248  compressionConfig.depthParam[1] = depthQuantB;
249 
250  try
251  {
252  // Compress quantized disparity image
253  if (cv::imencode(".png", invDepthImg, compressedImage, params))
254  {
255  float cRatio = (float)(cv_ptr->image.rows * cv_ptr->image.cols * cv_ptr->image.elemSize())
256  / (float)compressedImage.size();
257  ROS_DEBUG("Compressed Depth Image Transport - Compression: 1:%.2f (%lu bytes)", cRatio, compressedImage.size());
258  }
259  else
260  {
261  ROS_ERROR("cv::imencode (png) failed on input image");
262  return sensor_msgs::CompressedImage::Ptr();
263  }
264  }
265  catch (cv::Exception& e)
266  {
267  ROS_ERROR("%s", e.msg.c_str());
268  return sensor_msgs::CompressedImage::Ptr();
269  }
270  }
271  }
272  // Raw depth map compression
273  else if ((bitDepth == 16) && (numChannels == 1))
274  {
275  // OpenCV-ROS bridge
276  cv_bridge::CvImagePtr cv_ptr;
277  try
278  {
279  cv_ptr = cv_bridge::toCvCopy(message);
280  }
281  catch (Exception& e)
282  {
283  ROS_ERROR("%s", e.msg.c_str());
284  return sensor_msgs::CompressedImage::Ptr();
285  }
286 
287  const Mat& depthImg = cv_ptr->image;
288  size_t rows = depthImg.rows;
289  size_t cols = depthImg.cols;
290 
291  if ((rows > 0) && (cols > 0))
292  {
293  unsigned short depthMaxUShort = static_cast<unsigned short>(depth_max * 1000.0f);
294 
295  // Matrix iterators
296  MatIterator_<unsigned short> itDepthImg = cv_ptr->image.begin<unsigned short>(),
297  itDepthImg_end = cv_ptr->image.end<unsigned short>();
298 
299  // Max depth filter
300  for (; itDepthImg != itDepthImg_end; ++itDepthImg)
301  {
302  if (*itDepthImg > depthMaxUShort)
303  *itDepthImg = 0;
304  }
305 
306  // Compress raw depth image
307  if (cv::imencode(".png", cv_ptr->image, compressedImage, params))
308  {
309  float cRatio = (float)(cv_ptr->image.rows * cv_ptr->image.cols * cv_ptr->image.elemSize())
310  / (float)compressedImage.size();
311  ROS_DEBUG("Compressed Depth Image Transport - Compression: 1:%.2f (%lu bytes)", cRatio, compressedImage.size());
312  }
313  else
314  {
315  ROS_ERROR("cv::imencode (png) failed on input image");
316  return sensor_msgs::CompressedImage::Ptr();
317  }
318  }
319  }
320  else
321  {
322  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());
323  return sensor_msgs::CompressedImage::Ptr();
324  }
325 
326  if (compressedImage.size() > 0)
327  {
328  // Add configuration to binary output
329  compressed->data.resize(sizeof(ConfigHeader));
330  memcpy(&compressed->data[0], &compressionConfig, sizeof(ConfigHeader));
331 
332  // Add compressed binary data to messages
333  compressed->data.insert(compressed->data.end(), compressedImage.begin(), compressedImage.end());
334 
335  return compressed;
336  }
337 
338  return sensor_msgs::CompressedImage::Ptr();
339 }
340 
341 } // namespace compressed_depth_image_transport
sensor_msgs::Image::Ptr decodeCompressedDepthImage(const sensor_msgs::CompressedImage &compressed_image)
Definition: codec.cpp:64
CvImagePtr toCvCopy(const sensor_msgs::ImageConstPtr &source, const std::string &encoding=std::string())
#define ROS_ERROR(...)
sensor_msgs::CompressedImage::Ptr encodeCompressedDepthImage(const sensor_msgs::Image &message, double depth_max, double depth_quantization, int png_level)
Definition: codec.cpp:164
#define ROS_DEBUG(...)


compressed_depth_image_transport
Author(s): Julius Kammerl
autogenerated on Tue Jul 2 2019 19:10:11