38 #include <opencv2/highgui/highgui.hpp> 39 #include <opencv2/imgproc/imgproc.hpp> 53 void CompressedSubscriber::subscribeImpl(
ros::NodeHandle& nh,
const std::string& base_topic, uint32_t queue_size,
58 Base::subscribeImpl(nh, base_topic, queue_size, callback, tracked_object, transport_hints);
61 reconfigure_server_ = boost::make_shared<ReconfigureServer>(this->nh());
62 ReconfigureServer::CallbackType
f = boost::bind(&CompressedSubscriber::configCb,
this, _1, _2);
63 reconfigure_server_->setCallback(f);
67 void CompressedSubscriber::configCb(
Config& config, uint32_t level)
70 if (config_.mode == compressed_image_transport::CompressedSubscriber_gray) {
71 imdecode_flag_ = cv::IMREAD_GRAYSCALE;
72 }
else if (config_.mode == compressed_image_transport::CompressedSubscriber_color) {
73 imdecode_flag_ = cv::IMREAD_COLOR;
75 imdecode_flag_ = cv::IMREAD_UNCHANGED;
79 void CompressedSubscriber::shutdown()
81 reconfigure_server_.reset();
85 void CompressedSubscriber::internalCallback(
const sensor_msgs::CompressedImageConstPtr& message,
93 cv_ptr->header = message->header;
98 cv_ptr->image = cv::imdecode(cv::Mat(message->data), imdecode_flag_);
101 const size_t split_pos = message->format.find(
';');
102 if (split_pos==std::string::npos)
105 switch (cv_ptr->image.channels())
108 cv_ptr->encoding = enc::MONO8;
111 cv_ptr->encoding = enc::BGR8;
114 ROS_ERROR(
"Unsupported number of channels: %i", cv_ptr->image.channels());
119 std::string image_encoding = message->format.substr(0, split_pos);
121 cv_ptr->encoding = image_encoding;
123 if ( enc::isColor(image_encoding))
125 std::string compressed_encoding = message->format.substr(split_pos);
126 bool compressed_bgr_image = (compressed_encoding.find(
"compressed bgr") != std::string::npos);
129 if (compressed_bgr_image)
132 if ((image_encoding == enc::RGB8) || (image_encoding == enc::RGB16))
133 cv::cvtColor(cv_ptr->image, cv_ptr->image, CV_BGR2RGB);
135 if ((image_encoding == enc::RGBA8) || (image_encoding == enc::RGBA16))
136 cv::cvtColor(cv_ptr->image, cv_ptr->image, CV_BGR2RGBA);
138 if ((image_encoding == enc::BGRA8) || (image_encoding == enc::BGRA16))
139 cv::cvtColor(cv_ptr->image, cv_ptr->image, CV_BGR2BGRA);
143 if ((image_encoding == enc::BGR8) || (image_encoding == enc::BGR16))
144 cv::cvtColor(cv_ptr->image, cv_ptr->image, CV_RGB2BGR);
146 if ((image_encoding == enc::BGRA8) || (image_encoding == enc::BGRA16))
147 cv::cvtColor(cv_ptr->image, cv_ptr->image, CV_RGB2BGRA);
149 if ((image_encoding == enc::RGBA8) || (image_encoding == enc::RGBA16))
150 cv::cvtColor(cv_ptr->image, cv_ptr->image, CV_RGB2RGBA);
155 catch (cv::Exception& e)
160 size_t rows = cv_ptr->image.rows;
161 size_t cols = cv_ptr->image.cols;
163 if ((rows > 0) && (cols > 0))
165 user_cb(cv_ptr->toImageMsg());
compressed_image_transport::CompressedSubscriberConfig Config
boost::function< void(const sensor_msgs::ImageConstPtr &)> Callback