compressed_subscriber.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 
37 #include <cv_bridge/cv_bridge.h>
38 #include <opencv2/highgui/highgui.hpp>
39 #include <opencv2/imgproc/imgproc.hpp>
40 
42 
43 #include <limits>
44 #include <vector>
45 
46 using namespace cv;
47 
49 
51 {
52 
53 void CompressedSubscriber::subscribeImpl(ros::NodeHandle& nh, const std::string& base_topic, uint32_t queue_size,
54  const Callback& callback, const ros::VoidPtr& tracked_object,
55  const image_transport::TransportHints& transport_hints)
56 {
58  Base::subscribeImpl(nh, base_topic, queue_size, callback, tracked_object, transport_hints);
59 
60  // Set up reconfigure server for this topic
61  reconfigure_server_ = boost::make_shared<ReconfigureServer>(this->nh());
62  ReconfigureServer::CallbackType f = boost::bind(&CompressedSubscriber::configCb, this, _1, _2);
63  reconfigure_server_->setCallback(f);
64 }
65 
66 
67 void CompressedSubscriber::configCb(Config& config, uint32_t level)
68 {
69  config_ = config;
70  if (config_.mode == compressed_image_transport::CompressedSubscriber_gray) {
71  imdecode_flag_ = cv::IMREAD_GRAYSCALE;
72  } else if (config_.mode == compressed_image_transport::CompressedSubscriber_color) {
73  imdecode_flag_ = cv::IMREAD_COLOR;
74  } else /*if (config_.mode == compressed_image_transport::CompressedSubscriber_unchanged)*/ {
75  imdecode_flag_ = cv::IMREAD_UNCHANGED;
76  }
77 }
78 
79 void CompressedSubscriber::shutdown()
80 {
81  reconfigure_server_.reset();
83 }
84 
85 void CompressedSubscriber::internalCallback(const sensor_msgs::CompressedImageConstPtr& message,
86  const Callback& user_cb)
87 
88 {
89 
91 
92  // Copy message header
93  cv_ptr->header = message->header;
94 
95  // Decode color/mono image
96  try
97  {
98  cv_ptr->image = cv::imdecode(cv::Mat(message->data), imdecode_flag_);
99 
100  // Assign image encoding string
101  const size_t split_pos = message->format.find(';');
102  if (split_pos==std::string::npos)
103  {
104  // Older version of compressed_image_transport does not signal image format
105  switch (cv_ptr->image.channels())
106  {
107  case 1:
108  cv_ptr->encoding = enc::MONO8;
109  break;
110  case 3:
111  cv_ptr->encoding = enc::BGR8;
112  break;
113  default:
114  ROS_ERROR("Unsupported number of channels: %i", cv_ptr->image.channels());
115  break;
116  }
117  } else
118  {
119  std::string image_encoding = message->format.substr(0, split_pos);
120 
121  cv_ptr->encoding = image_encoding;
122 
123  if ( enc::isColor(image_encoding))
124  {
125  std::string compressed_encoding = message->format.substr(split_pos);
126  bool compressed_bgr_image = (compressed_encoding.find("compressed bgr") != std::string::npos);
127 
128  // Revert color transformation
129  if (compressed_bgr_image)
130  {
131  // if necessary convert colors from bgr to rgb
132  if ((image_encoding == enc::RGB8) || (image_encoding == enc::RGB16))
133  cv::cvtColor(cv_ptr->image, cv_ptr->image, CV_BGR2RGB);
134 
135  if ((image_encoding == enc::RGBA8) || (image_encoding == enc::RGBA16))
136  cv::cvtColor(cv_ptr->image, cv_ptr->image, CV_BGR2RGBA);
137 
138  if ((image_encoding == enc::BGRA8) || (image_encoding == enc::BGRA16))
139  cv::cvtColor(cv_ptr->image, cv_ptr->image, CV_BGR2BGRA);
140  } else
141  {
142  // if necessary convert colors from rgb to bgr
143  if ((image_encoding == enc::BGR8) || (image_encoding == enc::BGR16))
144  cv::cvtColor(cv_ptr->image, cv_ptr->image, CV_RGB2BGR);
145 
146  if ((image_encoding == enc::BGRA8) || (image_encoding == enc::BGRA16))
147  cv::cvtColor(cv_ptr->image, cv_ptr->image, CV_RGB2BGRA);
148 
149  if ((image_encoding == enc::RGBA8) || (image_encoding == enc::RGBA16))
150  cv::cvtColor(cv_ptr->image, cv_ptr->image, CV_RGB2RGBA);
151  }
152  }
153  }
154  }
155  catch (cv::Exception& e)
156  {
157  ROS_ERROR("%s", e.what());
158  }
159 
160  size_t rows = cv_ptr->image.rows;
161  size_t cols = cv_ptr->image.cols;
162 
163  if ((rows > 0) && (cols > 0))
164  // Publish message to user callback
165  user_cb(cv_ptr->toImageMsg());
166 }
167 
168 } //namespace compressed_image_transport
f
compressed_image_transport::CompressedSubscriberConfig Config
boost::function< void(const sensor_msgs::ImageConstPtr &)> Callback
#define ROS_ERROR(...)


compressed_image_transport
Author(s): Patrick Mihelich, Julius Kammerl
autogenerated on Fri Sep 20 2019 03:32:14