40 #include <opencv2/highgui/highgui.hpp> 48 #ifndef CV_VERSION_EPOCH 49 #include <opencv2/imgcodecs.hpp> 52 #if CV_VERSION_MAJOR > 3 53 #include <opencv2/imgcodecs/legacy/constants_c.h> 70 cv_ptr->header = message.header;
73 std::string image_encoding = message.format.substr(0, message.format.find(
';'));
74 cv_ptr->encoding = image_encoding;
82 memcpy(&compressionConfig, &message.data[0],
sizeof(compressionConfig));
85 const std::vector<uint8_t> imageData(message.data.begin() +
sizeof(compressionConfig), message.data.end());
88 float depthQuantA, depthQuantB;
94 if (enc::bitDepth(image_encoding) == 32)
100 decompressed = cv::imdecode(imageData, cv::IMREAD_UNCHANGED);
102 catch (cv::Exception& e)
105 return sensor_msgs::Image::Ptr();
108 size_t rows = decompressed.rows;
109 size_t cols = decompressed.cols;
111 if ((rows > 0) && (cols > 0))
113 cv_ptr->image = Mat(rows, cols, CV_32FC1);
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>();
121 for (; (itDepthImg != itDepthImg_end) && (itInvDepthImg != itInvDepthImg_end); ++itDepthImg, ++itInvDepthImg)
126 *itDepthImg = depthQuantA / ((float)*itInvDepthImg - depthQuantB);
130 *itDepthImg = std::numeric_limits<float>::quiet_NaN();
135 return cv_ptr->toImageMsg();
143 cv_ptr->image = cv::imdecode(imageData, CV_LOAD_IMAGE_UNCHANGED);
145 catch (cv::Exception& e)
148 return sensor_msgs::Image::Ptr();
151 size_t rows = cv_ptr->image.rows;
152 size_t cols = cv_ptr->image.cols;
154 if ((rows > 0) && (cols > 0))
157 return cv_ptr->toImageMsg();
161 return sensor_msgs::Image::Ptr();
165 const sensor_msgs::Image& message,
166 double depth_max,
double depth_quantization,
int png_level)
170 sensor_msgs::CompressedImage::Ptr compressed(
new sensor_msgs::CompressedImage());
171 compressed->header = message.header;
172 compressed->format = message.encoding;
175 std::vector<int> params;
179 int bitDepth = enc::bitDepth(message.encoding);
180 int numChannels = enc::numChannels(message.encoding);
187 std::vector<uint8_t> compressedImage;
190 compressed->format +=
"; compressedDepth";
193 params[0] = cv::IMWRITE_PNG_COMPRESSION;
194 params[1] = png_level;
196 if ((bitDepth == 32) && (numChannels == 1))
198 float depthZ0 = depth_quantization;
199 float depthMax = depth_max;
210 return sensor_msgs::CompressedImage::Ptr();
213 const Mat& depthImg = cv_ptr->image;
214 size_t rows = depthImg.rows;
215 size_t cols = depthImg.cols;
217 if ((rows > 0) && (cols > 0))
220 Mat invDepthImg(rows, cols, CV_16UC1);
223 float depthQuantA = depthZ0 * (depthZ0 + 1.0f);
224 float depthQuantB = 1.0f - depthQuantA / depthMax;
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>();
233 for (; (itDepthImg != itDepthImg_end) && (itInvDepthImg != itInvDepthImg_end); ++itDepthImg, ++itInvDepthImg)
236 if (*itDepthImg < depthMax)
238 *itInvDepthImg = depthQuantA / *itDepthImg + depthQuantB;
247 compressionConfig.
depthParam[0] = depthQuantA;
248 compressionConfig.
depthParam[1] = depthQuantB;
253 if (cv::imencode(
".png", invDepthImg, compressedImage, params))
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());
261 ROS_ERROR(
"cv::imencode (png) failed on input image");
262 return sensor_msgs::CompressedImage::Ptr();
265 catch (cv::Exception& e)
268 return sensor_msgs::CompressedImage::Ptr();
273 else if ((bitDepth == 16) && (numChannels == 1))
284 return sensor_msgs::CompressedImage::Ptr();
287 const Mat& depthImg = cv_ptr->image;
288 size_t rows = depthImg.rows;
289 size_t cols = depthImg.cols;
291 if ((rows > 0) && (cols > 0))
293 unsigned short depthMaxUShort =
static_cast<unsigned short>(depth_max * 1000.0f);
296 MatIterator_<unsigned short> itDepthImg = cv_ptr->image.begin<
unsigned short>(),
297 itDepthImg_end = cv_ptr->image.end<
unsigned short>();
300 for (; itDepthImg != itDepthImg_end; ++itDepthImg)
302 if (*itDepthImg > depthMaxUShort)
307 if (cv::imencode(
".png", cv_ptr->image, compressedImage, params))
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());
315 ROS_ERROR(
"cv::imencode (png) failed on input image");
316 return sensor_msgs::CompressedImage::Ptr();
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();
326 if (compressedImage.size() > 0)
330 memcpy(&compressed->data[0], &compressionConfig,
sizeof(
ConfigHeader));
333 compressed->data.insert(compressed->data.end(), compressedImage.begin(), compressedImage.end());
338 return sensor_msgs::CompressedImage::Ptr();
sensor_msgs::Image::Ptr decodeCompressedDepthImage(const sensor_msgs::CompressedImage &compressed_image)
CvImagePtr toCvCopy(const sensor_msgs::ImageConstPtr &source, const std::string &encoding=std::string())
sensor_msgs::CompressedImage::Ptr encodeCompressedDepthImage(const sensor_msgs::Image &message, double depth_max, double depth_quantization, int png_level)