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_publisher.h"
00036 #include <cv_bridge/cv_bridge.h>
00037 #include <sensor_msgs/image_encodings.h>
00038 #include <opencv2/highgui/highgui.hpp>
00039 #include <opencv2/imgcodecs.hpp>
00040 #include <boost/make_shared.hpp>
00041
00042 #include "compressed_image_transport/compression_common.h"
00043
00044 #include <vector>
00045 #include <sstream>
00046
00047
00048 #if CV_VERSION_MAJOR > 3
00049 #include <opencv2/imgcodecs/legacy/constants_c.h>
00050 #endif
00051
00052 using namespace cv;
00053 using namespace std;
00054
00055 namespace enc = sensor_msgs::image_encodings;
00056
00057 namespace compressed_image_transport
00058 {
00059
00060 void CompressedPublisher::advertiseImpl(ros::NodeHandle &nh, const std::string &base_topic, uint32_t queue_size,
00061 const image_transport::SubscriberStatusCallback &user_connect_cb,
00062 const image_transport::SubscriberStatusCallback &user_disconnect_cb,
00063 const ros::VoidPtr &tracked_object, bool latch)
00064 {
00065 typedef image_transport::SimplePublisherPlugin<sensor_msgs::CompressedImage> Base;
00066 Base::advertiseImpl(nh, base_topic, queue_size, user_connect_cb, user_disconnect_cb, tracked_object, latch);
00067
00068
00069 reconfigure_server_ = boost::make_shared<ReconfigureServer>(this->nh());
00070 ReconfigureServer::CallbackType f = boost::bind(&CompressedPublisher::configCb, this, _1, _2);
00071 reconfigure_server_->setCallback(f);
00072 }
00073
00074 void CompressedPublisher::configCb(Config& config, uint32_t level)
00075 {
00076 config_ = config;
00077 }
00078
00079 void CompressedPublisher::publish(const sensor_msgs::Image& message, const PublishFn& publish_fn) const
00080 {
00081
00082 sensor_msgs::CompressedImage compressed;
00083 compressed.header = message.header;
00084 compressed.format = message.encoding;
00085
00086
00087 std::vector<int> params;
00088
00089
00090 compressionFormat encodingFormat = UNDEFINED;
00091 if (config_.format == compressed_image_transport::CompressedPublisher_jpeg)
00092 encodingFormat = JPEG;
00093 if (config_.format == compressed_image_transport::CompressedPublisher_png)
00094 encodingFormat = PNG;
00095
00096
00097 int bitDepth = enc::bitDepth(message.encoding);
00098 int numChannels = enc::numChannels(message.encoding);
00099
00100 switch (encodingFormat)
00101 {
00102
00103 case JPEG:
00104 {
00105 params.resize(9, 0);
00106 params[0] = IMWRITE_JPEG_QUALITY;
00107 params[1] = config_.jpeg_quality;
00108 params[2] = IMWRITE_JPEG_PROGRESSIVE;
00109 params[3] = config_.jpeg_progressive ? 1 : 0;
00110 params[4] = IMWRITE_JPEG_OPTIMIZE;
00111 params[5] = config_.jpeg_optimize ? 1 : 0;
00112 params[6] = IMWRITE_JPEG_RST_INTERVAL;
00113 params[7] = config_.jpeg_restart_interval;
00114
00115
00116 compressed.format += "; jpeg compressed ";
00117
00118
00119 if ((bitDepth == 8) || (bitDepth == 16))
00120 {
00121
00122 std::string targetFormat;
00123 if (enc::isColor(message.encoding))
00124 {
00125
00126 targetFormat = "bgr8";
00127 compressed.format += targetFormat;
00128 }
00129
00130
00131 try
00132 {
00133 boost::shared_ptr<CompressedPublisher> tracked_object;
00134 cv_bridge::CvImageConstPtr cv_ptr = cv_bridge::toCvShare(message, tracked_object, targetFormat);
00135
00136
00137 if (cv::imencode(".jpg", cv_ptr->image, compressed.data, params))
00138 {
00139
00140 float cRatio = (float)(cv_ptr->image.rows * cv_ptr->image.cols * cv_ptr->image.elemSize())
00141 / (float)compressed.data.size();
00142 ROS_DEBUG("Compressed Image Transport - Codec: jpg, Compression Ratio: 1:%.2f (%lu bytes)", cRatio, compressed.data.size());
00143 }
00144 else
00145 {
00146 ROS_ERROR("cv::imencode (jpeg) failed on input image");
00147 }
00148 }
00149 catch (cv_bridge::Exception& e)
00150 {
00151 ROS_ERROR("%s", e.what());
00152 }
00153 catch (cv::Exception& e)
00154 {
00155 ROS_ERROR("%s", e.what());
00156 }
00157
00158
00159 publish_fn(compressed);
00160 }
00161 else
00162 ROS_ERROR("Compressed Image Transport - JPEG compression requires 8/16-bit color format (input format is: %s)", message.encoding.c_str());
00163
00164 break;
00165 }
00166
00167 case PNG:
00168 {
00169 params.resize(3, 0);
00170 params[0] = IMWRITE_PNG_COMPRESSION;
00171 params[1] = config_.png_level;
00172
00173
00174 compressed.format += "; png compressed ";
00175
00176
00177 if ((bitDepth == 8) || (bitDepth == 16))
00178 {
00179
00180
00181 stringstream targetFormat;
00182 if (enc::isColor(message.encoding))
00183 {
00184
00185 targetFormat << "bgr" << bitDepth;
00186 compressed.format += targetFormat.str();
00187 }
00188
00189
00190 try
00191 {
00192 boost::shared_ptr<CompressedPublisher> tracked_object;
00193 cv_bridge::CvImageConstPtr cv_ptr = cv_bridge::toCvShare(message, tracked_object, targetFormat.str());
00194
00195
00196 if (cv::imencode(".png", cv_ptr->image, compressed.data, params))
00197 {
00198
00199 float cRatio = (float)(cv_ptr->image.rows * cv_ptr->image.cols * cv_ptr->image.elemSize())
00200 / (float)compressed.data.size();
00201 ROS_DEBUG("Compressed Image Transport - Codec: png, Compression Ratio: 1:%.2f (%lu bytes)", cRatio, compressed.data.size());
00202 }
00203 else
00204 {
00205 ROS_ERROR("cv::imencode (png) failed on input image");
00206 }
00207 }
00208 catch (cv_bridge::Exception& e)
00209 {
00210 ROS_ERROR("%s", e.what());
00211 return;
00212 }
00213 catch (cv::Exception& e)
00214 {
00215 ROS_ERROR("%s", e.what());
00216 return;
00217 }
00218
00219
00220 publish_fn(compressed);
00221 }
00222 else
00223 ROS_ERROR("Compressed Image Transport - PNG compression requires 8/16-bit encoded color format (input format is: %s)", message.encoding.c_str());
00224 break;
00225 }
00226
00227 default:
00228 ROS_ERROR("Unknown compression type '%s', valid options are 'jpeg' and 'png'", config_.format.c_str());
00229 break;
00230 }
00231
00232 }
00233
00234 }