40 #include <opencv2/highgui/highgui.hpp> 49 #ifndef CV_VERSION_EPOCH 50 #include <opencv2/imgcodecs.hpp> 53 #if CV_VERSION_MAJOR > 3 54 #include <opencv2/imgcodecs/legacy/constants_c.h> 70 cv_ptr->header = message.header;
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;
77 if (split_pos == std::string::npos) {
78 compression_format =
"png";
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";
86 ROS_ERROR(
"Unsupported image format: %s", message.format.c_str());
87 return sensor_msgs::Image::Ptr();
91 cv_ptr->encoding = image_encoding;
99 memcpy(&compressionConfig, &message.data[0],
sizeof(compressionConfig));
102 const std::vector<uint8_t> imageData(message.data.begin() +
sizeof(compressionConfig), message.data.end());
105 float depthQuantA, depthQuantB;
108 depthQuantA = compressionConfig.
depthParam[0];
109 depthQuantB = compressionConfig.
depthParam[1];
111 if (enc::bitDepth(image_encoding) == 32)
113 cv::Mat decompressed;
114 if (compression_format ==
"png") {
118 decompressed = cv::imdecode(imageData, cv::IMREAD_UNCHANGED);
120 catch (cv::Exception& e)
123 return sensor_msgs::Image::Ptr();
125 }
else if (compression_format ==
"rvl") {
126 const unsigned char *buffer = imageData.data();
128 memcpy(&cols, &buffer[0], 4);
129 memcpy(&rows, &buffer[4], 4);
130 decompressed = Mat(rows, cols, CV_16UC1);
132 rvl.
DecompressRVL(&buffer[8], decompressed.ptr<
unsigned short>(), cols * rows);
134 return sensor_msgs::Image::Ptr();
137 size_t rows = decompressed.rows;
138 size_t cols = decompressed.cols;
140 if ((rows > 0) && (cols > 0))
142 cv_ptr->image = Mat(rows, cols, CV_32FC1);
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>();
150 for (; (itDepthImg != itDepthImg_end) && (itInvDepthImg != itInvDepthImg_end); ++itDepthImg, ++itInvDepthImg)
155 *itDepthImg = depthQuantA / ((float)*itInvDepthImg - depthQuantB);
159 *itDepthImg = std::numeric_limits<float>::quiet_NaN();
164 return cv_ptr->toImageMsg();
170 if (compression_format ==
"png") {
173 cv_ptr->image = cv::imdecode(imageData, CV_LOAD_IMAGE_UNCHANGED);
175 catch (cv::Exception& e)
178 return sensor_msgs::Image::Ptr();
180 }
else if (compression_format ==
"rvl") {
181 const unsigned char *buffer = imageData.data();
183 memcpy(&cols, &buffer[0], 4);
184 memcpy(&rows, &buffer[4], 4);
185 cv_ptr->image = Mat(rows, cols, CV_16UC1);
187 rvl.
DecompressRVL(&buffer[8], cv_ptr->image.ptr<
unsigned short>(), cols * rows);
189 return sensor_msgs::Image::Ptr();
192 size_t rows = cv_ptr->image.rows;
193 size_t cols = cv_ptr->image.cols;
195 if ((rows > 0) && (cols > 0))
198 return cv_ptr->toImageMsg();
202 return sensor_msgs::Image::Ptr();
206 const sensor_msgs::Image& message,
207 const std::string& compression_format,
208 double depth_max,
double depth_quantization,
int png_level)
212 sensor_msgs::CompressedImage::Ptr compressed(
new sensor_msgs::CompressedImage());
213 compressed->header = message.header;
214 compressed->format = message.encoding;
217 std::vector<int> params;
221 int bitDepth = enc::bitDepth(message.encoding);
222 int numChannels = enc::numChannels(message.encoding);
229 std::vector<uint8_t> compressedImage;
232 compressed->format +=
"; compressedDepth " + compression_format;
235 params[0] = cv::IMWRITE_PNG_COMPRESSION;
236 params[1] = png_level;
238 if ((bitDepth == 32) && (numChannels == 1))
240 float depthZ0 = depth_quantization;
241 float depthMax = depth_max;
252 return sensor_msgs::CompressedImage::Ptr();
255 const Mat& depthImg = cv_ptr->image;
256 size_t rows = depthImg.rows;
257 size_t cols = depthImg.cols;
259 if ((rows > 0) && (cols > 0))
262 Mat invDepthImg(rows, cols, CV_16UC1);
265 float depthQuantA = depthZ0 * (depthZ0 + 1.0f);
266 float depthQuantB = 1.0f - depthQuantA / depthMax;
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>();
275 for (; (itDepthImg != itDepthImg_end) && (itInvDepthImg != itInvDepthImg_end); ++itDepthImg, ++itInvDepthImg)
278 if (*itDepthImg < depthMax)
280 *itInvDepthImg = depthQuantA / *itDepthImg + depthQuantB;
289 compressionConfig.
depthParam[0] = depthQuantA;
290 compressionConfig.
depthParam[1] = depthQuantB;
293 if (compression_format ==
"png") {
296 if (cv::imencode(
".png", invDepthImg, compressedImage, params))
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());
304 ROS_ERROR(
"cv::imencode (png) failed on input image");
305 return sensor_msgs::CompressedImage::Ptr();
308 catch (cv::Exception& e)
311 return sensor_msgs::CompressedImage::Ptr();
313 }
else if (compression_format ==
"rvl") {
314 int numPixels = invDepthImg.rows * invDepthImg.cols;
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);
322 int compressedSize = rvl.
CompressRVL(invDepthImg.ptr<
unsigned short>(), &compressedImage[8], numPixels);
323 compressedImage.resize(8 + compressedSize);
328 else if ((bitDepth == 16) && (numChannels == 1))
339 return sensor_msgs::CompressedImage::Ptr();
342 const Mat& depthImg = cv_ptr->image;
343 size_t rows = depthImg.rows;
344 size_t cols = depthImg.cols;
346 if ((rows > 0) && (cols > 0))
348 unsigned short depthMaxUShort =
static_cast<unsigned short>(depth_max * 1000.0f);
351 MatIterator_<unsigned short> itDepthImg = cv_ptr->image.begin<
unsigned short>(),
352 itDepthImg_end = cv_ptr->image.end<
unsigned short>();
355 for (; itDepthImg != itDepthImg_end; ++itDepthImg)
357 if (*itDepthImg > depthMaxUShort)
362 if (compression_format ==
"png") {
363 if (cv::imencode(
".png", cv_ptr->image, compressedImage, params))
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());
371 ROS_ERROR(
"cv::imencode (png) failed on input image");
372 return sensor_msgs::CompressedImage::Ptr();
374 }
else if (compression_format ==
"rvl") {
375 int numPixels = cv_ptr->image.rows * cv_ptr->image.cols;
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);
383 int compressedSize = rvl.
CompressRVL(cv_ptr->image.ptr<
unsigned short>(), &compressedImage[8], numPixels);
384 compressedImage.resize(8 + compressedSize);
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();
394 if (compressedImage.size() > 0)
398 memcpy(&compressed->data[0], &compressionConfig,
sizeof(
ConfigHeader));
401 compressed->data.insert(compressed->data.end(), compressedImage.begin(), compressedImage.end());
406 return sensor_msgs::CompressedImage::Ptr();
sensor_msgs::Image::Ptr decodeCompressedDepthImage(const sensor_msgs::CompressedImage &compressed_image)
sensor_msgs::CompressedImage::Ptr encodeCompressedDepthImage(const sensor_msgs::Image &message, const std::string &compression_format, double depth_max, double depth_quantization, int png_level)
CvImagePtr toCvCopy(const sensor_msgs::ImageConstPtr &source, const std::string &encoding=std::string())
void DecompressRVL(const unsigned char *input, unsigned short *output, int numPixels)
int CompressRVL(const unsigned short *input, unsigned char *output, int numPixels)