adding_images_nodelet.cpp
Go to the documentation of this file.
1 // -*- mode: c++ -*-
2 /*********************************************************************
3  * Software License Agreement (BSD License)
4  *
5  * Copyright (c) JSK, 2016 Lab
6  * All rights reserved.
7  *
8  * Redistribution and use in source and binary forms, with or without
9  * modification, are permitted provided that the following conditions
10  * are met:
11  *
12  * * Redistributions of source code must retain the above copyright
13  * notice, this list of conditions and the following disclaimer.
14  * * Redistributions in binary form must reproduce the above
15  * copyright notice, this list of conditions and the following
16  * disclaimer in the documentation and/or other materials provided
17  * with the distribution.
18  * * Neither the name of the JSK Lab nor the names of its
19  * contributors may be used to endorse or promote products derived
20  * from this software without specific prior written permission.
21  *
22  * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
23  * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
24  * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
25  * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
26  * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
27  * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
28  * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
29  * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
30  * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
31  * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
32  * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
33  * POSSIBILITY OF SUCH DAMAGE.
34  *********************************************************************/
35 
36 // https://github.com/opencv/opencv/tree/2.4/samples/cpp/tutorial_code/ImgProc/AddingImages.cpp
41 #include <opencv2/opencv.hpp>
42 #include <cv_bridge/cv_bridge.h>
44 #include <sensor_msgs/CameraInfo.h>
45 #include <dynamic_reconfigure/server.h>
46 
49 
54 
55 #include "opencv_apps/AddingImagesConfig.h"
56 #include "opencv_apps/nodelet.h"
57 
58 namespace opencv_apps
59 {
60 class AddingImagesNodelet : public opencv_apps::Nodelet
61 {
62 private:
64 
71 
73  // Dynamic Reconfigure
75  typedef opencv_apps::AddingImagesConfig Config;
76  typedef dynamic_reconfigure::Server<Config> ReconfigureServer;
79 
80  int queue_size_;
81  bool debug_view_;
83 
84  std::string window_name_;
85 
93  boost::mutex mutex_;
94 
95  bool approximate_sync_;
96  double alpha_;
97  double beta_;
98  double gamma_;
99 
100  void imageCallbackWithInfo(const sensor_msgs::ImageConstPtr& msg1, const sensor_msgs::ImageConstPtr& msg2,
101  const sensor_msgs::CameraInfoConstPtr& cam_info)
102  {
103  doWork(msg1, msg2, cam_info->header.frame_id);
104  }
105 
106  void imageCallback(const sensor_msgs::ImageConstPtr& msg1, const sensor_msgs::ImageConstPtr& msg2)
107  {
108  doWork(msg1, msg2, msg1->header.frame_id);
109  }
110 
111  void subscribe() // NOLINT(modernize-use-override)
112  {
113  NODELET_DEBUG("Subscribing to image topic.");
114  sub_image1_.subscribe(*it_, "image1", 3);
115  sub_image2_.subscribe(*it_, "image2", 3);
116  sub_camera_info_.subscribe(*nh_, "camera_info", 3);
117  if (config_.use_camera_info)
118  {
119  if (approximate_sync_)
120  {
122  boost::make_shared<message_filters::Synchronizer<ApproxSyncPolicyWithCameraInfo> >(queue_size_);
124  async_with_info_->registerCallback(boost::bind(&AddingImagesNodelet::imageCallbackWithInfo, this,
127  }
128  else
129  {
130  sync_with_info_ = boost::make_shared<message_filters::Synchronizer<SyncPolicyWithCameraInfo> >(queue_size_);
132  sync_with_info_->registerCallback(boost::bind(&AddingImagesNodelet::imageCallbackWithInfo, this,
135  }
136  }
137  else
138  {
140  {
141  async_ = boost::make_shared<message_filters::Synchronizer<ApproxSyncPolicy> >(queue_size_);
142  async_->connectInput(sub_image1_, sub_image2_);
143  async_->registerCallback(
145  }
146  else
147  {
148  sync_ = boost::make_shared<message_filters::Synchronizer<SyncPolicy> >(queue_size_);
149  sync_->connectInput(sub_image1_, sub_image2_);
150  sync_->registerCallback(
152  }
153  }
154  }
155 
156  void unsubscribe() // NOLINT(modernize-use-override)
157  {
158  NODELET_DEBUG("Unsubscribing from image topic.");
162  }
163 
164  void reconfigureCallback(Config& config, uint32_t level)
165  {
166  boost::mutex::scoped_lock lock(mutex_);
167  config_ = config;
168  alpha_ = config.alpha;
169  if (config.auto_beta)
170  {
171  beta_ = 1.0 - alpha_;
172  config.beta = beta_;
173  }
174  else
175  {
176  beta_ = config.beta;
177  }
178  gamma_ = config.gamma;
179  }
180 
181  void doWork(const sensor_msgs::Image::ConstPtr& image_msg1, const sensor_msgs::Image::ConstPtr& image_msg2,
182  const std::string& input_frame_from_msg)
183  {
184  boost::mutex::scoped_lock lock(mutex_);
185  // Work on the image.
186  try
187  {
188  cv::Mat image1 = cv_bridge::toCvCopy(image_msg1, image_msg1->encoding)->image;
189  cv::Mat image2 = cv_bridge::toCvCopy(image_msg2, image_msg1->encoding)->image;
190  if (cv_bridge::getCvType(image_msg1->encoding) != cv_bridge::getCvType(image_msg2->encoding))
191  {
192  NODELET_ERROR("Encoding of input images must be same type: %s, %s", image_msg1->encoding.c_str(),
193  image_msg2->encoding.c_str());
194  return;
195  }
196 
197  cv::Mat result_image;
198  if (image1.rows != image2.rows || image1.cols != image2.cols)
199  {
200  int new_rows = std::max(image1.rows, image2.rows);
201  int new_cols = std::max(image1.cols, image2.cols);
202  // if ( new_rows != image1.rows || new_cols != image1.cols ) {
203  cv::Mat image1_tmp = cv::Mat(new_rows, new_cols, image1.type());
204  image1.copyTo(image1_tmp(cv::Rect(0, 0, image1.cols, image1.rows)));
205  image1 = image1_tmp.clone(); // need clone because of toCvShare??
206 
207  // if ( new_rows != image2.rows || new_cols != image2.cols ) {
208  cv::Mat image2_tmp = cv::Mat(new_rows, new_cols, image2.type());
209  image2.copyTo(image2_tmp(cv::Rect(0, 0, image2.cols, image2.rows)));
210  image2 = image2_tmp.clone();
211  }
212  cv::addWeighted(image1, alpha_, image2, beta_, gamma_, result_image);
213  //-- Show what you got
214  sensor_msgs::ImagePtr image_msg3 =
215  cv_bridge::CvImage(image_msg1->header, image_msg1->encoding, result_image).toImageMsg();
216  if (debug_view_)
217  {
218  cv::namedWindow(window_name_, cv::WINDOW_AUTOSIZE);
219 #ifdef CV_BRIDGE_CVT_COLOR_FOR_DISPLAY_IS_NOT_SUPPORTED
220  cv::imshow(window_name_, result_image);
221 #else
222 #ifdef CV_BRIDGE_CVT_COLOR_FOR_DISPLAY_OPTION_IS_NOT_SUPPORTED
223  cv::imshow(window_name_,
224  cv_bridge::cvtColorForDisplay(cv_bridge::toCvShare(image_msg3, image_msg3->encoding))->image);
225 #else
227  if (sensor_msgs::image_encodings::bitDepth(image_msg1->encoding) == 32 ||
228  sensor_msgs::image_encodings::bitDepth(image_msg1->encoding) == 64)
229  {
230  // float or double image
231  options.do_dynamic_scaling = true;
232  }
233  cv::imshow(window_name_, cv_bridge::cvtColorForDisplay(cv_bridge::toCvShare(image_msg3), "", options)->image);
234 #endif
235 #endif
236  int c = cv::waitKey(1);
237  }
238  img_pub_.publish(image_msg3);
239  }
240  catch (cv::Exception& e)
241  {
242  NODELET_ERROR("Image processing error: %s %s %s %i", e.err.c_str(), e.func.c_str(), e.file.c_str(), e.line);
243  }
244 
245  prev_stamp_ = image_msg1->header.stamp;
246  }
247 
248 public:
249  virtual void onInit() // NOLINT(modernize-use-override)
250  {
251  Nodelet::onInit();
253 
254  pnh_->param("debug_view", debug_view_, false);
255  if (debug_view_)
256  {
257  always_subscribe_ = true;
258  }
259  prev_stamp_ = ros::Time(0, 0);
260 
261  window_name_ = "AddingImages Demo";
263  // Dynamic Reconfigure
265  reconfigure_server_ = boost::make_shared<dynamic_reconfigure::Server<Config> >(*pnh_);
266  dynamic_reconfigure::Server<Config>::CallbackType f =
268  reconfigure_server_->setCallback(f);
269 
270  pnh_->param("approximate_sync", approximate_sync_, true);
271  pnh_->param("queue_size", queue_size_, 100);
272  img_pub_ = advertiseImage(*pnh_, "image", 1);
274  }
275 };
276 } // namespace opencv_apps
277 
278 namespace adding_images
279 {
281 {
282 public:
283  virtual void onInit() // NOLINT(modernize-use-override)
284  {
285  ROS_WARN("DeprecationWarning: Nodelet adding_images/adding_images is deprecated, "
286  "and renamed to opencv_apps/adding_images.");
288  }
289 };
290 } // namespace adding_images
291 
292 #ifdef USE_PLUGINLIB_CLASS_LIST_MACROS_H
294 #else
296 #endif
cv_bridge::CvtColorForDisplayOptions::do_dynamic_scaling
bool do_dynamic_scaling
opencv_apps::AddingImagesNodelet::gamma_
double gamma_
Definition: adding_images_nodelet.cpp:162
image_transport::SubscriberFilter
nodelet.h
opencv_apps::AddingImagesNodelet::approximate_sync_
bool approximate_sync_
Definition: adding_images_nodelet.cpp:159
NODELET_ERROR
#define NODELET_ERROR(...)
opencv_apps::Nodelet::onInitPostProcess
virtual void onInitPostProcess()
Post processing of initialization of nodelet. You need to call this method in order to use always_sub...
Definition: nodelet.cpp:77
image_encodings.h
image_transport::ImageTransport
opencv_apps::AddingImagesNodelet::sync_
boost::shared_ptr< message_filters::Synchronizer< SyncPolicy > > sync_
Definition: adding_images_nodelet.cpp:155
boost::shared_ptr< image_transport::ImageTransport >
cv_bridge::CvImage::toImageMsg
sensor_msgs::ImagePtr toImageMsg() const
cv_bridge::CvtColorForDisplayOptions
opencv_apps::AddingImagesNodelet::ReconfigureServer
dynamic_reconfigure::Server< Config > ReconfigureServer
Definition: adding_images_nodelet.cpp:140
opencv_apps::AddingImagesNodelet::subscribe
void subscribe()
This method is called when publisher is subscribed by other nodes. Set up subscribers in this method.
Definition: adding_images_nodelet.cpp:175
boost::placeholders::_1
boost::arg< 1 > _1
Definition: nodelet.cpp:44
opencv_apps::Nodelet
Nodelet to automatically subscribe/unsubscribe topics according to subscription of advertised topics.
Definition: nodelet.h:90
opencv_apps::AddingImagesNodelet::ApproxSyncPolicyWithCameraInfo
message_filters::sync_policies::ApproximateTime< sensor_msgs::Image, sensor_msgs::Image, sensor_msgs::CameraInfo > ApproxSyncPolicyWithCameraInfo
Definition: adding_images_nodelet.cpp:132
opencv_apps::AddingImagesNodelet::alpha_
double alpha_
Definition: adding_images_nodelet.cpp:160
opencv_apps::AddingImagesNodelet::window_name_
std::string window_name_
Definition: adding_images_nodelet.cpp:148
image_transport::SubscriberFilter::subscribe
void subscribe(ImageTransport &it, const std::string &base_topic, uint32_t queue_size, const TransportHints &transport_hints=TransportHints())
opencv_apps::AddingImagesNodelet::ApproxSyncPolicy
message_filters::sync_policies::ApproximateTime< sensor_msgs::Image, sensor_msgs::Image > ApproxSyncPolicy
Definition: adding_images_nodelet.cpp:134
opencv_apps::AddingImagesNodelet::it_
boost::shared_ptr< image_transport::ImageTransport > it_
Definition: adding_images_nodelet.cpp:127
message_filters::Subscriber::unsubscribe
void unsubscribe()
opencv_apps::AddingImagesNodelet::mutex_
boost::mutex mutex_
Definition: adding_images_nodelet.cpp:157
f
f
message_filters::Subscriber< sensor_msgs::CameraInfo >
boost::placeholders::_3
boost::arg< 3 > _3
Definition: nodelet.cpp:46
opencv_apps::Nodelet::advertiseImage
image_transport::Publisher advertiseImage(ros::NodeHandle &nh, const std::string &topic, int queue_size)
Advertise an image topic and watch the publisher. Publishers which are created by this method....
Definition: nodelet.h:201
class_list_macros.h
opencv_apps::AddingImagesNodelet::sub_camera_info_
message_filters::Subscriber< sensor_msgs::CameraInfo > sub_camera_info_
Definition: adding_images_nodelet.cpp:152
opencv_apps::AddingImagesNodelet
Definition: adding_images_nodelet.cpp:92
message_filters::sync_policies::ApproximateTime
opencv_apps::AddingImagesNodelet::reconfigure_server_
boost::shared_ptr< ReconfigureServer > reconfigure_server_
Definition: adding_images_nodelet.cpp:142
cv_bridge::cvtColorForDisplay
CvImageConstPtr cvtColorForDisplay(const CvImageConstPtr &source, const std::string &encoding=std::string(), const CvtColorForDisplayOptions options=CvtColorForDisplayOptions())
subscriber_filter.h
cv_bridge::toCvCopy
CvImagePtr toCvCopy(const sensor_msgs::CompressedImage &source, const std::string &encoding=std::string())
subscriber.h
opencv_apps::AddingImagesNodelet::async_with_info_
boost::shared_ptr< message_filters::Synchronizer< ApproxSyncPolicyWithCameraInfo > > async_with_info_
Definition: adding_images_nodelet.cpp:154
boost::placeholders::_2
boost::arg< 2 > _2
Definition: nodelet.cpp:45
adding_images::AddingImagesNodelet::onInit
virtual void onInit()
Initialize nodehandles nh_ and pnh_. Subclass should call this method in its onInit method.
Definition: adding_images_nodelet.cpp:283
opencv_apps::Nodelet::always_subscribe_
bool always_subscribe_
A flag to disable watching mechanism and always subscribe input topics. It can be specified via ~alwa...
Definition: nodelet.h:300
ROS_WARN
#define ROS_WARN(...)
opencv_apps::AddingImagesNodelet::debug_view_
bool debug_view_
Definition: adding_images_nodelet.cpp:145
PLUGINLIB_EXPORT_CLASS
PLUGINLIB_EXPORT_CLASS(opencv_apps::AddingImagesNodelet, nodelet::Nodelet)
adding_images
Definition: adding_images_nodelet.cpp:278
opencv_apps::AddingImagesNodelet::reconfigureCallback
void reconfigureCallback(Config &config, uint32_t level)
Definition: adding_images_nodelet.cpp:228
opencv_apps::AddingImagesNodelet::imageCallbackWithInfo
void imageCallbackWithInfo(const sensor_msgs::ImageConstPtr &msg1, const sensor_msgs::ImageConstPtr &msg2, const sensor_msgs::CameraInfoConstPtr &cam_info)
Definition: adding_images_nodelet.cpp:164
image_transport::Publisher::publish
void publish(const sensor_msgs::Image &message) const
opencv_apps
Demo code to calculate moments.
Definition: nodelet.h:68
sensor_msgs::image_encodings::bitDepth
static int bitDepth(const std::string &encoding)
image_transport.h
exact_time.h
message_filters::Subscriber::subscribe
void subscribe()
opencv_apps::AddingImagesNodelet::Config
opencv_apps::AddingImagesConfig Config
Definition: adding_images_nodelet.cpp:139
opencv_apps::AddingImagesNodelet::sync_with_info_
boost::shared_ptr< message_filters::Synchronizer< SyncPolicyWithCameraInfo > > sync_with_info_
Definition: adding_images_nodelet.cpp:153
nodelet::Nodelet
ros::Time
opencv_apps::AddingImagesNodelet::sub_image1_
image_transport::SubscriberFilter sub_image1_
Definition: adding_images_nodelet.cpp:150
opencv_apps::AddingImagesNodelet::beta_
double beta_
Definition: adding_images_nodelet.cpp:161
image_transport::Publisher
cv_bridge.h
opencv_apps::AddingImagesNodelet::img_pub_
image_transport::Publisher img_pub_
Definition: adding_images_nodelet.cpp:151
opencv_apps::AddingImagesNodelet::unsubscribe
void unsubscribe()
This method is called when publisher is unsubscribed by other nodes. Shut down subscribers in this me...
Definition: adding_images_nodelet.cpp:220
opencv_apps::AddingImagesNodelet::async_
boost::shared_ptr< message_filters::Synchronizer< ApproxSyncPolicy > > async_
Definition: adding_images_nodelet.cpp:156
cv_bridge::CvImage
class_list_macros.hpp
synchronizer.h
opencv_apps::AddingImagesNodelet::onInit
virtual void onInit()
Initialize nodehandles nh_ and pnh_. Subclass should call this method in its onInit method.
Definition: adding_images_nodelet.cpp:313
opencv_apps::AddingImagesNodelet::SyncPolicy
message_filters::sync_policies::ExactTime< sensor_msgs::Image, sensor_msgs::Image > SyncPolicy
Definition: adding_images_nodelet.cpp:133
opencv_apps::AddingImagesNodelet::imageCallback
void imageCallback(const sensor_msgs::ImageConstPtr &msg1, const sensor_msgs::ImageConstPtr &msg2)
Definition: adding_images_nodelet.cpp:170
approximate_time.h
opencv_apps::AddingImagesNodelet::prev_stamp_
ros::Time prev_stamp_
Definition: adding_images_nodelet.cpp:146
opencv_apps::AddingImagesNodelet::sub_image2_
image_transport::SubscriberFilter sub_image2_
Definition: adding_images_nodelet.cpp:150
cv_bridge::toCvShare
CvImageConstPtr toCvShare(const sensor_msgs::Image &source, const boost::shared_ptr< void const > &tracked_object, const std::string &encoding=std::string())
opencv_apps::AddingImagesNodelet::doWork
void doWork(const sensor_msgs::Image::ConstPtr &image_msg1, const sensor_msgs::Image::ConstPtr &image_msg2, const std::string &input_frame_from_msg)
Definition: adding_images_nodelet.cpp:245
cv_bridge::getCvType
int getCvType(const std::string &encoding)
message_filters::sync_policies::ExactTime
opencv_apps::AddingImagesNodelet::SyncPolicyWithCameraInfo
message_filters::sync_policies::ExactTime< sensor_msgs::Image, sensor_msgs::Image, sensor_msgs::CameraInfo > SyncPolicyWithCameraInfo
Definition: adding_images_nodelet.cpp:130
opencv_apps::Nodelet::nh_
boost::shared_ptr< ros::NodeHandle > nh_
Shared pointer to nodehandle.
Definition: nodelet.h:272
opencv_apps::AddingImagesNodelet::config_
Config config_
Definition: adding_images_nodelet.cpp:141
adding_images::AddingImagesNodelet
Definition: adding_images_nodelet.cpp:280
image_transport::SubscriberFilter::unsubscribe
void unsubscribe()
opencv_apps::Nodelet::onInit
virtual void onInit()
Initialize nodehandles nh_ and pnh_. Subclass should call this method in its onInit method.
Definition: nodelet.cpp:60
opencv_apps::Nodelet::pnh_
boost::shared_ptr< ros::NodeHandle > pnh_
Shared pointer to private nodehandle.
Definition: nodelet.h:277
opencv_apps::AddingImagesNodelet::queue_size_
int queue_size_
Definition: adding_images_nodelet.cpp:144
NODELET_DEBUG
#define NODELET_DEBUG(...)


opencv_apps
Author(s): Kei Okada
autogenerated on Fri May 23 2025 02:49:49