compressed_publisher.cpp
Go to the documentation of this file.
1 /*********************************************************************
2 * Software License Agreement (BSD License)
3 *
4 * Copyright (c) 20012, 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 <boost/make_shared.hpp>
40 
42 
43 #include <vector>
44 #include <sstream>
45 
46 // If OpenCV4
47 #if CV_VERSION_MAJOR > 3
48 #include <opencv2/imgcodecs/legacy/constants_c.h>
49 #endif
50 
51 using namespace cv;
52 using namespace std;
53 
55 
57 {
58 
59 void CompressedPublisher::advertiseImpl(ros::NodeHandle &nh, const std::string &base_topic, uint32_t queue_size,
60  const image_transport::SubscriberStatusCallback &user_connect_cb,
61  const image_transport::SubscriberStatusCallback &user_disconnect_cb,
62  const ros::VoidPtr &tracked_object, bool latch)
63 {
65  Base::advertiseImpl(nh, base_topic, queue_size, user_connect_cb, user_disconnect_cb, tracked_object, latch);
66 
67  // Set up reconfigure server for this topic
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);
71 }
72 
73 void CompressedPublisher::configCb(Config& config, uint32_t level)
74 {
75  config_ = config;
76 }
77 
78 void CompressedPublisher::publish(const sensor_msgs::Image& message, const PublishFn& publish_fn) const
79 {
80  // Compressed image message
81  sensor_msgs::CompressedImage compressed;
82  compressed.header = message.header;
83  compressed.format = message.encoding;
84 
85  // Compression settings
86  std::vector<int> params;
87  params.resize(3, 0);
88 
89  // Get codec configuration
90  compressionFormat encodingFormat = UNDEFINED;
91  if (config_.format == compressed_image_transport::CompressedPublisher_jpeg)
92  encodingFormat = JPEG;
93  if (config_.format == compressed_image_transport::CompressedPublisher_png)
94  encodingFormat = PNG;
95 
96  // Bit depth of image encoding
97  int bitDepth = enc::bitDepth(message.encoding);
98  int numChannels = enc::numChannels(message.encoding);
99 
100  switch (encodingFormat)
101  {
102  // JPEG Compression
103  case JPEG:
104  {
105  params[0] = CV_IMWRITE_JPEG_QUALITY;
106  params[1] = config_.jpeg_quality;
107 
108  // Update ros message format header
109  compressed.format += "; jpeg compressed ";
110 
111  // Check input format
112  if ((bitDepth == 8) || (bitDepth == 16))
113  {
114  // Target image format
115  std::string targetFormat;
116  if (enc::isColor(message.encoding))
117  {
118  // convert color images to BGR8 format
119  targetFormat = "bgr8";
120  compressed.format += targetFormat;
121  }
122 
123  // OpenCV-ros bridge
124  try
125  {
127  cv_bridge::CvImageConstPtr cv_ptr = cv_bridge::toCvShare(message, tracked_object, targetFormat);
128 
129  // Compress image
130  if (cv::imencode(".jpg", cv_ptr->image, compressed.data, params))
131  {
132 
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());
136  }
137  else
138  {
139  ROS_ERROR("cv::imencode (jpeg) failed on input image");
140  }
141  }
142  catch (cv_bridge::Exception& e)
143  {
144  ROS_ERROR("%s", e.what());
145  }
146  catch (cv::Exception& e)
147  {
148  ROS_ERROR("%s", e.what());
149  }
150 
151  // Publish message
152  publish_fn(compressed);
153  }
154  else
155  ROS_ERROR("Compressed Image Transport - JPEG compression requires 8/16-bit color format (input format is: %s)", message.encoding.c_str());
156 
157  break;
158  }
159  // PNG Compression
160  case PNG:
161  {
162  params[0] = CV_IMWRITE_PNG_COMPRESSION;
163  params[1] = config_.png_level;
164 
165  // Update ros message format header
166  compressed.format += "; png compressed ";
167 
168  // Check input format
169  if ((bitDepth == 8) || (bitDepth == 16))
170  {
171 
172  // Target image format
173  stringstream targetFormat;
174  if (enc::isColor(message.encoding))
175  {
176  // convert color images to RGB domain
177  targetFormat << "bgr" << bitDepth;
178  compressed.format += targetFormat.str();
179  }
180 
181  // OpenCV-ros bridge
182  try
183  {
185  cv_bridge::CvImageConstPtr cv_ptr = cv_bridge::toCvShare(message, tracked_object, targetFormat.str());
186 
187  // Compress image
188  if (cv::imencode(".png", cv_ptr->image, compressed.data, params))
189  {
190 
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());
194  }
195  else
196  {
197  ROS_ERROR("cv::imencode (png) failed on input image");
198  }
199  }
200  catch (cv_bridge::Exception& e)
201  {
202  ROS_ERROR("%s", e.what());
203  return;
204  }
205  catch (cv::Exception& e)
206  {
207  ROS_ERROR("%s", e.what());
208  return;
209  }
210 
211  // Publish message
212  publish_fn(compressed);
213  }
214  else
215  ROS_ERROR("Compressed Image Transport - PNG compression requires 8/16-bit encoded color format (input format is: %s)", message.encoding.c_str());
216  break;
217  }
218 
219  default:
220  ROS_ERROR("Unknown compression type '%s', valid options are 'jpeg' and 'png'", config_.format.c_str());
221  break;
222  }
223 
224 }
225 
226 } //namespace compressed_image_transport
CvImageConstPtr toCvShare(const sensor_msgs::ImageConstPtr &source, const std::string &encoding=std::string())
f
boost::function< void(const SingleSubscriberPublisher &)> SubscriberStatusCallback
compressed_image_transport::CompressedPublisherConfig Config
JPEG
#define ROS_ERROR(...)
#define ROS_DEBUG(...)
PNG


compressed_image_transport
Author(s): Patrick Mihelich, Julius Kammerl, David Gossow
autogenerated on Fri Feb 10 2023 03:31:21