fuse_images.cpp
Go to the documentation of this file.
1 /*********************************************************************
2  * Software License Agreement (BSD License)
3  *
4  * Copyright (c) 2017, Kentaro Wada and JSK Lab
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/o2r other materials provided
16  * with the distribution.
17  * * Neither the name of Kentaro Wada and JSK Lab 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 
35 #include <limits>
36 #include <string>
37 #include <vector>
38 
39 #include <opencv2/opencv.hpp>
40 
41 #include <cv_bridge/cv_bridge.h>
44 
45 
46 namespace jsk_pcl_ros
47 {
49  {
50  DiagnosticNodelet::onInit();
51  pub_out_ = advertise<sensor_msgs::Image>(*pnh_, "output", 1);
53  }
54 
56  {
57  pnh_->param("approximate_sync", approximate_sync_, true);
58  pnh_->param("queue_size", queue_size_, 10);
59  pnh_->param("averaging", averaging_, true); // TODO: -> dynparam
60 
61  XmlRpc::XmlRpcValue input_topics;
62  if (!pnh_->getParam("input_topics", input_topics))
63  {
64  NODELET_ERROR("Rosparam '~input_topics' is required.");
65  return;
66  }
67  if (input_topics.getType() != XmlRpc::XmlRpcValue::TypeArray)
68  {
69  NODELET_ERROR("Invalid type of '~input_topics' is specified. String array is expected.");
70  return;
71  }
72 
73  // Subscribe to the filters
74  filters_.resize(input_topics.size());
75 
76  // 8 topics
78  {
80  sensor_msgs::Image, sensor_msgs::Image, sensor_msgs::Image, sensor_msgs::Image,
81  sensor_msgs::Image, sensor_msgs::Image, sensor_msgs::Image, sensor_msgs::Image> >(queue_size_));
82  }
83  else
84  {
86  sensor_msgs::Image, sensor_msgs::Image, sensor_msgs::Image, sensor_msgs::Image,
87  sensor_msgs::Image, sensor_msgs::Image, sensor_msgs::Image, sensor_msgs::Image> > (queue_size_));
88  }
89 
90  // First input_topics.size() filters are valid
91  ROS_INFO("Subscribing to %d topics user given topics as inputs:", input_topics.size());
92  for (size_t i = 0; i < input_topics.size (); i++)
93  {
94  ROS_INFO_STREAM(" - " << (std::string)(input_topics[i]));
96  filters_[i]->subscribe(*pnh_, (std::string)(input_topics[i]), queue_size_);
97  }
98 
99  // Bogus null filter
100  filters_[0]->registerCallback(bind(&FuseDepthImages::input_callback, this, _1));
101 
102  if (input_topics.size() == 2)
103  {
104  if (approximate_sync_)
105  {
106  async_->connectInput(*filters_[0], *filters_[1], nf_, nf_, nf_, nf_, nf_, nf_);
107  }
108  else
109  {
110  sync_->connectInput(*filters_[0], *filters_[1], nf_, nf_, nf_, nf_, nf_, nf_);
111  }
112  }
113  else if (input_topics.size() == 3)
114  {
115  if (approximate_sync_)
116  {
117  async_->connectInput(*filters_[0], *filters_[1], *filters_[2], nf_, nf_, nf_, nf_, nf_);
118  }
119  else
120  {
121  sync_->connectInput(*filters_[0], *filters_[1], *filters_[2], nf_, nf_, nf_, nf_, nf_);
122  }
123  }
124  else if (input_topics.size() == 4)
125  {
126  if (approximate_sync_)
127  {
128  async_->connectInput(*filters_[0], *filters_[1], *filters_[2], *filters_[3], nf_, nf_, nf_, nf_);
129  }
130  else
131  {
132  sync_->connectInput(*filters_[0], *filters_[1], *filters_[2], *filters_[3], nf_, nf_, nf_, nf_);
133  }
134  }
135  else if (input_topics.size() == 5)
136  {
137  if (approximate_sync_)
138  {
139  async_->connectInput(*filters_[0], *filters_[1], *filters_[2], *filters_[3], *filters_[4], nf_, nf_, nf_);
140  }
141  else
142  {
143  sync_->connectInput(*filters_[0], *filters_[1], *filters_[2], *filters_[3], *filters_[4], nf_, nf_, nf_);
144  }
145  }
146  else if (input_topics.size() == 6)
147  {
148  if (approximate_sync_)
149  {
150  async_->connectInput(*filters_[0], *filters_[1], *filters_[2], *filters_[3], *filters_[4],
151  *filters_[5], nf_, nf_);
152  }
153  else
154  {
155  sync_->connectInput(*filters_[0], *filters_[1], *filters_[2], *filters_[3], *filters_[4],
156  *filters_[5], nf_, nf_);
157  }
158  }
159  else if (input_topics.size() == 7)
160  {
161  if (approximate_sync_)
162  {
163  async_->connectInput(*filters_[0], *filters_[1], *filters_[2], *filters_[3], *filters_[4],
164  *filters_[5], *filters_[6], nf_);
165  }
166  else
167  {
168  sync_->connectInput(*filters_[0], *filters_[1], *filters_[2], *filters_[3], *filters_[4],
169  *filters_[5], *filters_[6], nf_);
170  }
171  }
172  else if (input_topics.size() == 8)
173  {
174  if (approximate_sync_)
175  {
176  async_->connectInput(*filters_[0], *filters_[1], *filters_[2], *filters_[3], *filters_[4],
177  *filters_[5], *filters_[6], *filters_[7]);
178  }
179  else
180  {
181  sync_->connectInput(*filters_[0], *filters_[1], *filters_[2], *filters_[3], *filters_[4],
182  *filters_[5], *filters_[6], *filters_[7]);
183  }
184  }
185  else
186  {
187  NODELET_ERROR("Invalid number of topics is specified: %d. It must be > 1 and <= 8.", input_topics.size());
188  return;
189  }
190 
191  if (approximate_sync_)
192  {
193  async_->registerCallback(boost::bind(&FuseDepthImages::inputCb, this, _1, _2, _3, _4, _5, _6, _7, _8));
194  }
195  else
196  {
197  sync_->registerCallback(boost::bind(&FuseDepthImages::inputCb, this, _1, _2, _3, _4, _5, _6, _7, _8));
198  }
199  }
200 
202  {
203  for (size_t i = 0; i < filters_.size(); i++) {
204  filters_[i]->unsubscribe();
205  }
206  }
207 
209  const sensor_msgs::Image::ConstPtr& in,
210  const int height_expected,
211  const int width_expected,
212  std::vector<cv::Mat>& inputs)
213  {
214  if (in->height == 0 && in->width == 0)
215  {
216  // No subscription.
217  return false;
218  }
219  if (in->height != height_expected || in->width != width_expected)
220  {
221  NODELET_ERROR_THROTTLE(10, "Input images must have same size: height=%d, width=%d.",
222  height_expected, width_expected);
223  return false;
224  }
225  if (in->encoding != encoding_)
226  {
227  NODELET_ERROR_THROTTLE(10, "Input images must have same encoding. Expected: %s, Actual: %s",
228  encoding_.c_str(), in->encoding.c_str());
229  return false;
230  }
231  inputs.push_back(cv_bridge::toCvShare(in, encoding_)->image);
232  return true;
233  }
234 
236  const sensor_msgs::Image::ConstPtr& in1, const sensor_msgs::Image::ConstPtr& in2,
237  const sensor_msgs::Image::ConstPtr& in3, const sensor_msgs::Image::ConstPtr& in4,
238  const sensor_msgs::Image::ConstPtr& in5, const sensor_msgs::Image::ConstPtr& in6,
239  const sensor_msgs::Image::ConstPtr& in7, const sensor_msgs::Image::ConstPtr& in8)
240  {
241  int height = in1->height;
242  int width = in1->width;
243  std::vector<cv::Mat> inputs;
244  validateInput(in1, height, width, inputs);
245  validateInput(in2, height, width, inputs);
246  validateInput(in3, height, width, inputs);
247  validateInput(in4, height, width, inputs);
248  validateInput(in5, height, width, inputs);
249  validateInput(in6, height, width, inputs);
250  validateInput(in7, height, width, inputs);
251  validateInput(in8, height, width, inputs);
252 
253  cv::Mat out = fuseInputs(inputs);
255  }
256 
257  cv::Mat FuseDepthImages::fuseInputs(const std::vector<cv::Mat> inputs)
258  {
259  cv::Mat out(inputs[0].rows, inputs[0].cols, cv_bridge::getCvType(encoding_));
260  out.setTo(std::numeric_limits<float>::quiet_NaN());
261  for (size_t j = 0; j < inputs[0].rows; j++)
262  {
263  for (size_t i = 0; i < inputs[0].cols; i++)
264  {
265  int n_fused = 0;
266  float value_fused = 0;
267  for (size_t k = 0; k < inputs.size(); k++)
268  {
269  float value = inputs[k].at<float>(j, i);
270  if (!std::isnan(value))
271  {
272  value_fused += value;
273  n_fused += 1;
274  }
275  }
276  if (n_fused > 0)
277  {
278  out.at<float>(j, i) = value_fused / n_fused;
279  }
280  }
281  }
282  return out;
283  }
284 
285  cv::Mat FuseRGBImages::fuseInputs(const std::vector<cv::Mat> inputs)
286  {
287  cv::Mat out(inputs[0].rows, inputs[0].cols, cv_bridge::getCvType(encoding_));
288  out.setTo(cv::Scalar(0, 0, 0));
289  for (size_t j = 0; j < inputs[0].rows; j++)
290  {
291  for (size_t i = 0; i < inputs[0].cols; i++)
292  {
293  int n_fused = 0;
294  cv::Vec3b value_fused(0, 0, 0);
295  for (size_t k = 0; k < inputs.size(); k++)
296  {
297  cv::Vec3b value = inputs[k].at<cv::Vec3b>(j, i);
298  if (value[0] != 0 || value[1] != 0 || value[2] != 0)
299  {
300  if (!averaging_ && n_fused > 0)
301  {
302  continue;
303  }
304  value_fused += value;
305  n_fused += 1;
306  }
307  }
308  if (n_fused > 0)
309  {
310  out.at<cv::Vec3b>(j, i) = value_fused / n_fused;
311  }
312  }
313  }
314  return out;
315  }
316 
317 } // namespace jsk_pcl_ros
318 
CvImageConstPtr toCvShare(const sensor_msgs::ImageConstPtr &source, const std::string &encoding=std::string())
boost::shared_ptr< message_filters::Synchronizer< message_filters::sync_policies::ApproximateTime< sensor_msgs::Image, sensor_msgs::Image, sensor_msgs::Image, sensor_msgs::Image, sensor_msgs::Image, sensor_msgs::Image, sensor_msgs::Image, sensor_msgs::Image > > > async_
Synchronizer.
Definition: fuse_images.h:82
virtual void subscribe()
Definition: fuse_images.cpp:55
virtual bool validateInput(const sensor_msgs::Image::ConstPtr &in, const int height_expected, const int width_expected, std::vector< cv::Mat > &inputs)
#define NODELET_ERROR(...)
virtual void unsubscribe()
void publish(const boost::shared_ptr< M > &message) const
void input_callback(const sensor_msgs::Image::ConstPtr &input)
Input point cloud callback. Because we want to use the same synchronizer object, we push back empty e...
Definition: fuse_images.h:92
int size() const
#define NODELET_ERROR_THROTTLE(rate,...)
PLUGINLIB_EXPORT_CLASS(jsk_pcl_ros::FuseDepthImages, nodelet::Nodelet)
value
Type const & getType() const
#define ROS_INFO(...)
boost::shared_ptr< ros::NodeHandle > pnh_
virtual cv::Mat fuseInputs(std::vector< cv::Mat > inputs)
Definition: fuse_images.h:104
virtual cv::Mat fuseInputs(std::vector< cv::Mat > inputs)
virtual void inputCb(const sensor_msgs::Image::ConstPtr &in1, const sensor_msgs::Image::ConstPtr &in2, const sensor_msgs::Image::ConstPtr &in3, const sensor_msgs::Image::ConstPtr &in4, const sensor_msgs::Image::ConstPtr &in5, const sensor_msgs::Image::ConstPtr &in6, const sensor_msgs::Image::ConstPtr &in7, const sensor_msgs::Image::ConstPtr &in8)
virtual void onInit()
Definition: fuse_images.cpp:48
int getCvType(const std::string &encoding)
std::vector< boost::shared_ptr< message_filters::Subscriber< sensor_msgs::Image > > > filters_
A vector of message filters.
Definition: fuse_images.h:75
#define ROS_INFO_STREAM(args)
height
message_filters::PassThrough< sensor_msgs::Image > nf_
Null passthrough filter, used for pushing empty elements in the synchronizer.
Definition: fuse_images.h:72
boost::shared_ptr< message_filters::Synchronizer< message_filters::sync_policies::ExactTime< sensor_msgs::Image, sensor_msgs::Image, sensor_msgs::Image, sensor_msgs::Image, sensor_msgs::Image, sensor_msgs::Image, sensor_msgs::Image, sensor_msgs::Image > > > sync_
Definition: fuse_images.h:85
ros::Publisher pub_out_
Definition: fuse_images.h:63
sensor_msgs::ImagePtr toImageMsg() const
virtual cv::Mat fuseInputs(std::vector< cv::Mat > inputs)
width


jsk_pcl_ros
Author(s): Yohei Kakiuchi
autogenerated on Mon May 3 2021 03:03:46