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 <opencv2/highgui/highgui.hpp>
00039 #include <opencv2/imgproc/imgproc.hpp>
00040
00041 #include "compressed_image_transport/compression_common.h"
00042
00043 #include <limits>
00044 #include <vector>
00045
00046 using namespace cv;
00047
00048 namespace enc = sensor_msgs::image_encodings;
00049
00050 namespace compressed_image_transport
00051 {
00052
00053 void CompressedSubscriber::subscribeImpl(ros::NodeHandle& nh, const std::string& base_topic, uint32_t queue_size,
00054 const Callback& callback, const ros::VoidPtr& tracked_object,
00055 const image_transport::TransportHints& transport_hints)
00056 {
00057 typedef image_transport::SimpleSubscriberPlugin<sensor_msgs::CompressedImage> Base;
00058 Base::subscribeImpl(nh, base_topic, queue_size, callback, tracked_object, transport_hints);
00059
00060
00061 reconfigure_server_ = boost::make_shared<ReconfigureServer>(this->nh());
00062 ReconfigureServer::CallbackType f = boost::bind(&CompressedSubscriber::configCb, this, _1, _2);
00063 reconfigure_server_->setCallback(f);
00064 }
00065
00066
00067 void CompressedSubscriber::configCb(Config& config, uint32_t level)
00068 {
00069 config_ = config;
00070 if (config_.mode == compressed_image_transport::CompressedSubscriber_gray) {
00071 imdecode_flag_ = cv::IMREAD_GRAYSCALE;
00072 } else if (config_.mode == compressed_image_transport::CompressedSubscriber_color) {
00073 imdecode_flag_ = cv::IMREAD_COLOR;
00074 } else {
00075 imdecode_flag_ = cv::IMREAD_UNCHANGED;
00076 }
00077 }
00078
00079
00080 void CompressedSubscriber::internalCallback(const sensor_msgs::CompressedImageConstPtr& message,
00081 const Callback& user_cb)
00082
00083 {
00084
00085 cv_bridge::CvImagePtr cv_ptr(new cv_bridge::CvImage);
00086
00087
00088 cv_ptr->header = message->header;
00089
00090
00091 try
00092 {
00093 cv_ptr->image = cv::imdecode(cv::Mat(message->data), imdecode_flag_);
00094
00095
00096 const size_t split_pos = message->format.find(';');
00097 if (split_pos==std::string::npos)
00098 {
00099
00100 switch (cv_ptr->image.channels())
00101 {
00102 case 1:
00103 cv_ptr->encoding = enc::MONO8;
00104 break;
00105 case 3:
00106 cv_ptr->encoding = enc::BGR8;
00107 break;
00108 default:
00109 ROS_ERROR("Unsupported number of channels: %i", cv_ptr->image.channels());
00110 break;
00111 }
00112 } else
00113 {
00114 std::string image_encoding = message->format.substr(0, split_pos);
00115
00116 cv_ptr->encoding = image_encoding;
00117
00118 if ( enc::isColor(image_encoding))
00119 {
00120 std::string compressed_encoding = message->format.substr(split_pos);
00121 bool compressed_bgr_image = (compressed_encoding.find("compressed bgr") != std::string::npos);
00122
00123
00124 if (compressed_bgr_image)
00125 {
00126
00127 if ((image_encoding == enc::RGB8) || (image_encoding == enc::RGB16))
00128 cv::cvtColor(cv_ptr->image, cv_ptr->image, CV_BGR2RGB);
00129
00130 if ((image_encoding == enc::RGBA8) || (image_encoding == enc::RGBA16))
00131 cv::cvtColor(cv_ptr->image, cv_ptr->image, CV_BGR2RGBA);
00132
00133 if ((image_encoding == enc::BGRA8) || (image_encoding == enc::BGRA16))
00134 cv::cvtColor(cv_ptr->image, cv_ptr->image, CV_BGR2BGRA);
00135 } else
00136 {
00137
00138 if ((image_encoding == enc::BGR8) || (image_encoding == enc::BGR16))
00139 cv::cvtColor(cv_ptr->image, cv_ptr->image, CV_RGB2BGR);
00140
00141 if ((image_encoding == enc::BGRA8) || (image_encoding == enc::BGRA16))
00142 cv::cvtColor(cv_ptr->image, cv_ptr->image, CV_RGB2BGRA);
00143
00144 if ((image_encoding == enc::RGBA8) || (image_encoding == enc::RGBA16))
00145 cv::cvtColor(cv_ptr->image, cv_ptr->image, CV_RGB2RGBA);
00146 }
00147 }
00148 }
00149 }
00150 catch (cv::Exception& e)
00151 {
00152 ROS_ERROR("%s", e.what());
00153 }
00154
00155 size_t rows = cv_ptr->image.rows;
00156 size_t cols = cv_ptr->image.cols;
00157
00158 if ((rows > 0) && (cols > 0))
00159
00160 user_cb(cv_ptr->toImageMsg());
00161 }
00162
00163 }