38 #include <opencv2/highgui/highgui.hpp> 39 #include <opencv2/imgcodecs.hpp> 40 #include <boost/make_shared.hpp> 48 #if CV_VERSION_MAJOR > 3 49 #include <opencv2/imgcodecs/legacy/constants_c.h> 60 void CompressedPublisher::advertiseImpl(
ros::NodeHandle &nh,
const std::string &base_topic, uint32_t queue_size,
66 Base::advertiseImpl(nh, base_topic, queue_size, user_connect_cb, user_disconnect_cb, tracked_object, latch);
69 reconfigure_server_ = boost::make_shared<ReconfigureServer>(this->nh());
70 ReconfigureServer::CallbackType
f = boost::bind(&CompressedPublisher::configCb,
this, _1, _2);
71 reconfigure_server_->setCallback(f);
74 void CompressedPublisher::configCb(
Config& config, uint32_t level)
79 void CompressedPublisher::publish(
const sensor_msgs::Image& message,
const PublishFn& publish_fn)
const 82 sensor_msgs::CompressedImage compressed;
83 compressed.header = message.header;
84 compressed.format = message.encoding;
87 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)
106 params[0] = IMWRITE_JPEG_QUALITY;
107 params[1] = config_.jpeg_quality;
108 params[2] = IMWRITE_JPEG_PROGRESSIVE;
109 params[3] = config_.jpeg_progressive ? 1 : 0;
110 params[4] = IMWRITE_JPEG_OPTIMIZE;
111 params[5] = config_.jpeg_optimize ? 1 : 0;
112 params[6] = IMWRITE_JPEG_RST_INTERVAL;
113 params[7] = config_.jpeg_restart_interval;
116 compressed.format +=
"; jpeg compressed ";
119 if ((bitDepth == 8) || (bitDepth == 16))
122 std::string targetFormat;
123 if (enc::isColor(message.encoding))
126 targetFormat =
"bgr8";
127 compressed.format += targetFormat;
137 if (cv::imencode(
".jpg", cv_ptr->image, compressed.data, params))
140 float cRatio = (float)(cv_ptr->image.rows * cv_ptr->image.cols * cv_ptr->image.elemSize())
141 / (
float)compressed.data.size();
142 ROS_DEBUG(
"Compressed Image Transport - Codec: jpg, Compression Ratio: 1:%.2f (%lu bytes)", cRatio, compressed.data.size());
146 ROS_ERROR(
"cv::imencode (jpeg) failed on input image");
153 catch (cv::Exception& e)
159 publish_fn(compressed);
162 ROS_ERROR(
"Compressed Image Transport - JPEG compression requires 8/16-bit color format (input format is: %s)", message.encoding.c_str());
170 params[0] = IMWRITE_PNG_COMPRESSION;
171 params[1] = config_.png_level;
174 compressed.format +=
"; png compressed ";
177 if ((bitDepth == 8) || (bitDepth == 16))
181 stringstream targetFormat;
182 if (enc::isColor(message.encoding))
185 targetFormat <<
"bgr" << bitDepth;
186 compressed.format += targetFormat.str();
196 if (cv::imencode(
".png", cv_ptr->image, compressed.data, params))
199 float cRatio = (float)(cv_ptr->image.rows * cv_ptr->image.cols * cv_ptr->image.elemSize())
200 / (
float)compressed.data.size();
201 ROS_DEBUG(
"Compressed Image Transport - Codec: png, Compression Ratio: 1:%.2f (%lu bytes)", cRatio, compressed.data.size());
205 ROS_ERROR(
"cv::imencode (png) failed on input image");
213 catch (cv::Exception& e)
220 publish_fn(compressed);
223 ROS_ERROR(
"Compressed Image Transport - PNG compression requires 8/16-bit encoded color format (input format is: %s)", message.encoding.c_str());
228 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
boost::function< void(const sensor_msgs::CompressedImage &)> PublishFn
compressed_image_transport::CompressedPublisherConfig Config