Go to the documentation of this file.00001
00002
00003
00004
00005
00006
00007
00008
00009
00010
00011
00012
00013
00014
00015
00016
00017
00018
00019
00020
00021
00022
00023
00024
00025
00026
00027
00028
00029
00030
00031
00032
00033
00034
00035 #include "compressed_image_transport/compressed_subscriber.h"
00036 #include <sensor_msgs/image_encodings.h>
00037 #include <cv_bridge/cv_bridge.h>
00038 #include <opencv/cvwimage.h>
00039 #include <opencv/highgui.h>
00040 #include <opencv2/imgproc/imgproc.hpp>
00041
00042 #include "compressed_image_transport/compression_common.h"
00043
00044 #include <limits>
00045 #include <vector>
00046
00047 using namespace cv;
00048
00049 namespace enc = sensor_msgs::image_encodings;
00050
00051 namespace compressed_image_transport
00052 {
00053
00054 void CompressedSubscriber::internalCallback(const sensor_msgs::CompressedImageConstPtr& message,
00055 const Callback& user_cb)
00056
00057 {
00058
00059 cv_bridge::CvImagePtr cv_ptr(new cv_bridge::CvImage);
00060
00061
00062 cv_ptr->header = message->header;
00063
00064
00065 try
00066 {
00067 cv_ptr->image = cv::imdecode(cv::Mat(message->data), CV_LOAD_IMAGE_UNCHANGED);
00068
00069
00070 const size_t split_pos = message->format.find(';');
00071 if (split_pos==string::npos)
00072 {
00073
00074 switch (cv_ptr->image.channels())
00075 {
00076 case 1:
00077 cv_ptr->encoding = enc::MONO8;
00078 break;
00079 case 3:
00080 cv_ptr->encoding = enc::BGR8;
00081 break;
00082 default:
00083 ROS_ERROR("Unsupported number of channels: %i", cv_ptr->image.channels());
00084 break;
00085 }
00086 } else
00087 {
00088 string image_encoding = message->format.substr(0, split_pos);
00089
00090 cv_ptr->encoding = image_encoding;
00091
00092 if ( enc::isColor(image_encoding))
00093 {
00094 string compressed_encoding = message->format.substr(split_pos);
00095 bool compressed_bgr_image = (compressed_encoding.find("compressed bgr")!=string::npos);
00096
00097
00098 if (compressed_bgr_image)
00099 {
00100
00101 if ((image_encoding == enc::RGB8) || (image_encoding == enc::RGB16))
00102 cv::cvtColor(cv_ptr->image, cv_ptr->image, CV_BGR2RGB);
00103
00104 if ((image_encoding == enc::RGBA8) || (image_encoding == enc::RGBA16))
00105 cv::cvtColor(cv_ptr->image, cv_ptr->image, CV_BGR2RGBA);
00106
00107 if ((image_encoding == enc::BGRA8) || (image_encoding == enc::BGRA16))
00108 cv::cvtColor(cv_ptr->image, cv_ptr->image, CV_BGR2BGRA);
00109 } else
00110 {
00111
00112 if ((image_encoding == enc::BGR8) || (image_encoding == enc::BGR16))
00113 cv::cvtColor(cv_ptr->image, cv_ptr->image, CV_RGB2BGR);
00114
00115 if ((image_encoding == enc::BGRA8) || (image_encoding == enc::BGRA16))
00116 cv::cvtColor(cv_ptr->image, cv_ptr->image, CV_RGB2BGRA);
00117
00118 if ((image_encoding == enc::RGBA8) || (image_encoding == enc::RGBA16))
00119 cv::cvtColor(cv_ptr->image, cv_ptr->image, CV_RGB2RGBA);
00120 }
00121 }
00122 }
00123 }
00124 catch (cv::Exception& e)
00125 {
00126 ROS_ERROR("%s", e.what());
00127 }
00128
00129 size_t rows = cv_ptr->image.rows;
00130 size_t cols = cv_ptr->image.cols;
00131
00132 if ((rows > 0) && (cols > 0))
00133
00134 user_cb(cv_ptr->toImageMsg());
00135 }
00136
00137 }