Go to the documentation of this file.00001 #include "compressed_depth_image_transport/compressed_depth_subscriber.h"
00002 #include <sensor_msgs/image_encodings.h>
00003 #include <cv_bridge/cv_bridge.h>
00004 #include <opencv/cvwimage.h>
00005 #include <opencv/highgui.h>
00006 #include <opencv2/imgproc/imgproc.hpp>
00007
00008 #include "compressed_depth_image_transport/compression_common.h"
00009
00010 #include <limits>
00011 #include <vector>
00012
00013 using namespace cv;
00014
00015 namespace enc = sensor_msgs::image_encodings;
00016
00017 namespace compressed_depth_image_transport
00018 {
00019
00020 void CompressedDepthSubscriber::internalCallback(const sensor_msgs::CompressedImageConstPtr& message,
00021 const Callback& user_cb)
00022
00023 {
00024
00025 cv_bridge::CvImagePtr cv_ptr(new cv_bridge::CvImage);
00026
00027
00028 cv_ptr->header = message->header;
00029
00030
00031 string image_encoding = message->format.substr(0, message->format.find(';'));
00032 cv_ptr->encoding = image_encoding;
00033
00034
00035 if (message->data.size() > sizeof(ConfigHeader))
00036 {
00037
00038
00039 ConfigHeader compressionConfig;
00040 memcpy(&compressionConfig, &message->data[0], sizeof(compressionConfig));
00041
00042
00043 const vector<uint8_t> imageData(message->data.begin() + sizeof(compressionConfig), message->data.end());
00044
00045
00046 float depthQuantA, depthQuantB;
00047
00048
00049 depthQuantA = compressionConfig.depthParam[0];
00050 depthQuantB = compressionConfig.depthParam[1];
00051
00052 if (enc::bitDepth(image_encoding) == 32)
00053 {
00054 cv::Mat decompressed;
00055 try
00056 {
00057
00058 decompressed = cv::imdecode(imageData, CV_LOAD_IMAGE_UNCHANGED);
00059 }
00060 catch (cv::Exception& e)
00061 {
00062 ROS_ERROR("%s", e.what());
00063 }
00064
00065 size_t rows = decompressed.rows;
00066 size_t cols = decompressed.cols;
00067
00068 if ((rows > 0) && (cols > 0))
00069 {
00070 cv_ptr->image = Mat(rows, cols, CV_32FC1);
00071
00072
00073 MatIterator_<float> itDepthImg = cv_ptr->image.begin<float>(),
00074 itDepthImg_end = cv_ptr->image.end<float>();
00075 MatConstIterator_<unsigned short> itInvDepthImg = decompressed.begin<unsigned short>(),
00076 itInvDepthImg_end = decompressed.end<unsigned short>();
00077
00078 for (; (itDepthImg != itDepthImg_end) && (itInvDepthImg != itInvDepthImg_end); ++itDepthImg, ++itInvDepthImg)
00079 {
00080
00081 if (*itInvDepthImg)
00082 {
00083 *itDepthImg = depthQuantA / ((float)*itInvDepthImg - depthQuantB);
00084 }
00085 else
00086 {
00087 *itDepthImg = std::numeric_limits<float>::quiet_NaN();
00088 }
00089 }
00090
00091
00092 user_cb(cv_ptr->toImageMsg());
00093 }
00094 }
00095 else
00096 {
00097
00098 try
00099 {
00100 cv_ptr->image = cv::imdecode(imageData, CV_LOAD_IMAGE_UNCHANGED);
00101 }
00102 catch (cv::Exception& e)
00103 {
00104 ROS_ERROR("%s", e.what());
00105 }
00106
00107 size_t rows = cv_ptr->image.rows;
00108 size_t cols = cv_ptr->image.cols;
00109
00110 if ((rows > 0) && (cols > 0))
00111
00112 user_cb(cv_ptr->toImageMsg());
00113 }
00114 }
00115 }
00116
00117 }