compressed_publisher.cpp
Go to the documentation of this file.
1 /*********************************************************************
2 * Software License Agreement (BSD License)
3 *
4 * Copyright (c) 2012, Willow Garage, Inc.
5 * All rights reserved.
6 *
7 * Redistribution and use in source and binary forms, with or without
8 * modification, are permitted provided that the following conditions
9 * are met:
10 *
11 * * Redistributions of source code must retain the above copyright
12 * notice, this list of conditions and the following disclaimer.
13 * * Redistributions in binary form must reproduce the above
14 * copyright notice, this list of conditions and the following
15 * disclaimer in the documentation and/or other materials provided
16 * with the distribution.
17 * * Neither the name of the Willow Garage nor the names of its
18 * contributors may be used to endorse or promote products derived
19 * from this software without specific prior written permission.
20 *
21 * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
22 * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
23 * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
24 * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
25 * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
26 * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
27 * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
28 * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
29 * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
30 * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
31 * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
32 * POSSIBILITY OF SUCH DAMAGE.
33 *********************************************************************/
34 
36 #include <cv_bridge/cv_bridge.h>
38 #include <opencv2/highgui/highgui.hpp>
39 #include <opencv2/imgcodecs.hpp>
40 #include <boost/make_shared.hpp>
41 
43 
44 #include <vector>
45 #include <sstream>
46 
47 // If OpenCV4
48 #if CV_VERSION_MAJOR > 3
49 #include <opencv2/imgcodecs/legacy/constants_c.h>
50 #endif
51 
52 using namespace cv;
53 using namespace std;
54 
56 
58 {
59 
60 void CompressedPublisher::advertiseImpl(ros::NodeHandle &nh, const std::string &base_topic, uint32_t queue_size,
61  const image_transport::SubscriberStatusCallback &user_connect_cb,
62  const image_transport::SubscriberStatusCallback &user_disconnect_cb,
63  const ros::VoidPtr &tracked_object, bool latch)
64 {
66  Base::advertiseImpl(nh, base_topic, queue_size, user_connect_cb, user_disconnect_cb, tracked_object, latch);
67 
68  // Set up reconfigure server for this topic
69  reconfigure_server_ = boost::make_shared<ReconfigureServer>(this->nh());
70  ReconfigureServer::CallbackType f = boost::bind(&CompressedPublisher::configCb, this, boost::placeholders::_1, boost::placeholders::_2);
71  reconfigure_server_->setCallback(f);
72 }
73 
74 void CompressedPublisher::configCb(Config& config, uint32_t level)
75 {
76  config_ = config;
77 }
78 
79 void CompressedPublisher::publish(const sensor_msgs::Image& message, const PublishFn& publish_fn) const
80 {
81  if (!config_.enable) {
82  return;
83  }
84 
85  // Compressed image message
86  sensor_msgs::CompressedImage compressed;
87  compressed.header = message.header;
88  compressed.format = message.encoding;
89 
90  // Compression settings
91  std::vector<int> params;
92 
93  // Get codec configuration
94  compressionFormat encodingFormat = UNDEFINED;
95  if (config_.format == compressed_image_transport::CompressedPublisher_jpeg)
96  encodingFormat = JPEG;
97  if (config_.format == compressed_image_transport::CompressedPublisher_png)
98  encodingFormat = PNG;
99 
100  // Bit depth of image encoding
101  int bitDepth = enc::bitDepth(message.encoding);
102  int numChannels = enc::numChannels(message.encoding);
103 
104  switch (encodingFormat)
105  {
106  // JPEG Compression
107  case JPEG:
108  {
109  params.reserve(8);
110  params.emplace_back(IMWRITE_JPEG_QUALITY);
111  params.emplace_back(config_.jpeg_quality);
112  params.emplace_back(IMWRITE_JPEG_PROGRESSIVE);
113  params.emplace_back(config_.jpeg_progressive ? 1 : 0);
114  params.emplace_back(IMWRITE_JPEG_OPTIMIZE);
115  params.emplace_back(config_.jpeg_optimize ? 1 : 0);
116  params.emplace_back(IMWRITE_JPEG_RST_INTERVAL);
117  params.emplace_back(config_.jpeg_restart_interval);
118 
119  // Update ros message format header
120  compressed.format += "; jpeg compressed ";
121 
122  // Check input format
123  if ((bitDepth == 8) || (bitDepth == 16))
124  {
125  // Target image format
126  std::string targetFormat;
127  if (enc::isColor(message.encoding))
128  {
129  // convert color images to BGR8 format
130  targetFormat = "bgr8";
131  compressed.format += targetFormat;
132  }
133 
134  // OpenCV-ros bridge
135  try
136  {
138  cv_bridge::CvImageConstPtr cv_ptr = cv_bridge::toCvShare(message, tracked_object, targetFormat);
139 
140  // Compress image
141  if (cv::imencode(".jpg", cv_ptr->image, compressed.data, params))
142  {
143 
144  float cRatio = (float)(cv_ptr->image.rows * cv_ptr->image.cols * cv_ptr->image.elemSize())
145  / (float)compressed.data.size();
146  ROS_DEBUG("Compressed Image Transport - Codec: jpg, Compression Ratio: 1:%.2f (%lu bytes)", cRatio, compressed.data.size());
147  }
148  else
149  {
150  ROS_ERROR("cv::imencode (jpeg) failed on input image");
151  }
152  }
153  catch (cv_bridge::Exception& e)
154  {
155  ROS_ERROR("%s", e.what());
156  }
157  catch (cv::Exception& e)
158  {
159  ROS_ERROR("%s", e.what());
160  }
161 
162  // Publish message
163  publish_fn(compressed);
164  }
165  else
166  ROS_ERROR("Compressed Image Transport - JPEG compression requires 8/16-bit color format (input format is: %s)", message.encoding.c_str());
167 
168  break;
169  }
170  // PNG Compression
171  case PNG:
172  {
173  params.reserve(2);
174  params.emplace_back(IMWRITE_PNG_COMPRESSION);
175  params.emplace_back(config_.png_level);
176 
177  // Update ros message format header
178  compressed.format += "; png compressed ";
179 
180  // Check input format
181  if ((bitDepth == 8) || (bitDepth == 16))
182  {
183 
184  // Target image format
185  stringstream targetFormat;
186  if (enc::isColor(message.encoding))
187  {
188  // convert color images to RGB domain
189  targetFormat << "bgr" << bitDepth;
190  compressed.format += targetFormat.str();
191  }
192 
193  // OpenCV-ros bridge
194  try
195  {
197  cv_bridge::CvImageConstPtr cv_ptr = cv_bridge::toCvShare(message, tracked_object, targetFormat.str());
198 
199  // Compress image
200  if (cv::imencode(".png", cv_ptr->image, compressed.data, params))
201  {
202 
203  float cRatio = (float)(cv_ptr->image.rows * cv_ptr->image.cols * cv_ptr->image.elemSize())
204  / (float)compressed.data.size();
205  ROS_DEBUG("Compressed Image Transport - Codec: png, Compression Ratio: 1:%.2f (%lu bytes)", cRatio, compressed.data.size());
206  }
207  else
208  {
209  ROS_ERROR("cv::imencode (png) failed on input image");
210  }
211  }
212  catch (cv_bridge::Exception& e)
213  {
214  ROS_ERROR("%s", e.what());
215  return;
216  }
217  catch (cv::Exception& e)
218  {
219  ROS_ERROR("%s", e.what());
220  return;
221  }
222 
223  // Publish message
224  publish_fn(compressed);
225  }
226  else
227  ROS_ERROR("Compressed Image Transport - PNG compression requires 8/16-bit encoded color format (input format is: %s)", message.encoding.c_str());
228  break;
229  }
230 
231  default:
232  ROS_ERROR("Unknown compression type '%s', valid options are 'jpeg' and 'png'", config_.format.c_str());
233  break;
234  }
235 
236 }
237 
238 } //namespace compressed_image_transport
compressed_image_transport::CompressedPublisher::Config
compressed_image_transport::CompressedPublisherConfig Config
Definition: compressed_publisher.h:126
sensor_msgs::image_encodings
compressed_image_transport::compressionFormat
compressionFormat
Definition: compression_common.h:74
image_encodings.h
boost::shared_ptr< void >
PNG
PNG
JPEG
JPEG
cv_bridge::Exception
f
f
compressed_image_transport
Definition: compressed_publisher.h:40
ROS_DEBUG
#define ROS_DEBUG(...)
Base
std
image_transport::SimplePublisherPlugin< sensor_msgs::CompressedImage >
cv_bridge.h
ROS_ERROR
#define ROS_ERROR(...)
compressed_image_transport::UNDEFINED
@ UNDEFINED
Definition: compression_common.h:108
image_transport::SubscriberStatusCallback
boost::function< void(const SingleSubscriberPublisher &)> SubscriberStatusCallback
compression_common.h
cv_bridge::toCvShare
CvImageConstPtr toCvShare(const sensor_msgs::Image &source, const boost::shared_ptr< void const > &tracked_object, const std::string &encoding=std::string())
compressed_publisher.h
ros::NodeHandle


compressed_image_transport
Author(s): Patrick Mihelich, Julius Kammerl, David Gossow
autogenerated on Sat Jan 27 2024 03:31:06