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