38 #include <opencv2/highgui/highgui.hpp> 39 #include <boost/make_shared.hpp> 47 #if CV_VERSION_MAJOR > 3 48 #include <opencv2/imgcodecs/legacy/constants_c.h> 59 void CompressedPublisher::advertiseImpl(
ros::NodeHandle &nh,
const std::string &base_topic, uint32_t queue_size,
65 Base::advertiseImpl(nh, base_topic, queue_size, user_connect_cb, user_disconnect_cb, tracked_object, latch);
68 reconfigure_server_ = boost::make_shared<ReconfigureServer>(this->nh());
69 ReconfigureServer::CallbackType
f = boost::bind(&CompressedPublisher::configCb,
this, _1, _2);
70 reconfigure_server_->setCallback(f);
73 void CompressedPublisher::configCb(
Config& config, uint32_t level)
78 void CompressedPublisher::publish(
const sensor_msgs::Image& message,
const PublishFn& publish_fn)
const 81 sensor_msgs::CompressedImage compressed;
82 compressed.header = message.header;
83 compressed.format = message.encoding;
86 std::vector<int> params;
91 if (config_.format == compressed_image_transport::CompressedPublisher_jpeg)
92 encodingFormat =
JPEG;
93 if (config_.format == compressed_image_transport::CompressedPublisher_png)
97 int bitDepth = enc::bitDepth(message.encoding);
98 int numChannels = enc::numChannels(message.encoding);
100 switch (encodingFormat)
105 params[0] = CV_IMWRITE_JPEG_QUALITY;
106 params[1] = config_.jpeg_quality;
109 compressed.format +=
"; jpeg compressed ";
112 if ((bitDepth == 8) || (bitDepth == 16))
115 std::string targetFormat;
116 if (enc::isColor(message.encoding))
119 targetFormat =
"bgr8";
120 compressed.format += targetFormat;
130 if (cv::imencode(
".jpg", cv_ptr->image, compressed.data, params))
133 float cRatio = (float)(cv_ptr->image.rows * cv_ptr->image.cols * cv_ptr->image.elemSize())
134 / (
float)compressed.data.size();
135 ROS_DEBUG(
"Compressed Image Transport - Codec: jpg, Compression Ratio: 1:%.2f (%lu bytes)", cRatio, compressed.data.size());
139 ROS_ERROR(
"cv::imencode (jpeg) failed on input image");
146 catch (cv::Exception& e)
152 publish_fn(compressed);
155 ROS_ERROR(
"Compressed Image Transport - JPEG compression requires 8/16-bit color format (input format is: %s)", message.encoding.c_str());
162 params[0] = CV_IMWRITE_PNG_COMPRESSION;
163 params[1] = config_.png_level;
166 compressed.format +=
"; png compressed ";
169 if ((bitDepth == 8) || (bitDepth == 16))
173 stringstream targetFormat;
174 if (enc::isColor(message.encoding))
177 targetFormat <<
"bgr" << bitDepth;
178 compressed.format += targetFormat.str();
188 if (cv::imencode(
".png", cv_ptr->image, compressed.data, params))
191 float cRatio = (float)(cv_ptr->image.rows * cv_ptr->image.cols * cv_ptr->image.elemSize())
192 / (
float)compressed.data.size();
193 ROS_DEBUG(
"Compressed Image Transport - Codec: png, Compression Ratio: 1:%.2f (%lu bytes)", cRatio, compressed.data.size());
197 ROS_ERROR(
"cv::imencode (png) failed on input image");
205 catch (cv::Exception& e)
212 publish_fn(compressed);
215 ROS_ERROR(
"Compressed Image Transport - PNG compression requires 8/16-bit encoded color format (input format is: %s)", message.encoding.c_str());
220 ROS_ERROR(
"Unknown compression type '%s', valid options are 'jpeg' and 'png'", config_.format.c_str());
CvImageConstPtr toCvShare(const sensor_msgs::ImageConstPtr &source, const std::string &encoding=std::string())
boost::function< void(const SingleSubscriberPublisher &)> SubscriberStatusCallback
compressed_image_transport::CompressedPublisherConfig Config