smoothing_nodelet.cpp
Go to the documentation of this file.
1 // -*- mode: c++ -*-
2 /*********************************************************************
3  * Software License Agreement (BSD License)
4  *
5  * Copyright (c) 2016, JSK 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/blob/2.4/samples/cpp/tutorial_code/ImgProc/Smoothing.cpp
43 #include <ros/ros.h>
44 #include "opencv_apps/nodelet.h"
47 #include <cv_bridge/cv_bridge.h>
48 
49 #include <iostream>
50 #include <vector>
51 
52 #include "opencv2/imgproc/imgproc.hpp"
53 #include "opencv2/highgui/highgui.hpp"
54 #include "opencv2/features2d/features2d.hpp"
55 
56 #include <dynamic_reconfigure/server.h>
57 #include "opencv_apps/SmoothingConfig.h"
58 
61 
62 namespace opencv_apps
63 {
65 {
70 
72 
73  typedef opencv_apps::SmoothingConfig Config;
74  typedef dynamic_reconfigure::Server<Config> ReconfigureServer;
77 
81 
82  std::string window_name_;
83  static bool need_config_update_;
84 
86 
87  void reconfigureCallback(Config& new_config, uint32_t level)
88  {
89  config_ = new_config;
90  kernel_size_ = (config_.kernel_size / 2) * 2 + 1; // kernel_size must be odd number
91  }
92 
93  const std::string& frameWithDefault(const std::string& frame, const std::string& image_frame)
94  {
95  if (frame.empty())
96  return image_frame;
97  return frame;
98  }
99 
100  void imageCallbackWithInfo(const sensor_msgs::ImageConstPtr& msg, const sensor_msgs::CameraInfoConstPtr& cam_info)
101  {
102  doWork(msg, cam_info->header.frame_id);
103  }
104 
105  void imageCallback(const sensor_msgs::ImageConstPtr& msg)
106  {
107  doWork(msg, msg->header.frame_id);
108  }
109 
110  static void trackbarCallback(int /*unused*/, void* /*unused*/)
111  {
112  need_config_update_ = true;
113  }
114 
115  void doWork(const sensor_msgs::ImageConstPtr& msg, const std::string& input_frame_from_msg)
116  {
117  // Work on the image.
118  try
119  {
120  // Convert the image into something opencv can handle.
121  cv::Mat in_image = cv_bridge::toCvShare(msg, sensor_msgs::image_encodings::BGR8)->image;
122 
123  if (debug_view_)
124  {
126  char kernel_label[] = "Kernel Size : ";
127 
128  cv::namedWindow(window_name_, cv::WINDOW_AUTOSIZE);
129  cv::createTrackbar(kernel_label, window_name_, &kernel_size_, MAX_KERNEL_LENGTH, trackbarCallback);
131  {
132  kernel_size_ = (kernel_size_ / 2) * 2 + 1; // kernel_size must be odd number
133  config_.kernel_size = kernel_size_;
134  reconfigure_server_->updateConfig(config_);
135  need_config_update_ = false;
136  }
137  }
138 
139  cv::Mat out_image = in_image.clone();
140  int i = kernel_size_;
141  switch (config_.filter_type)
142  {
143  case opencv_apps::Smoothing_Homogeneous_Blur:
144  {
146  ROS_DEBUG_STREAM("Applying Homogeneous blur with kernel size " << i);
147  cv::blur(in_image, out_image, cv::Size(i, i), cv::Point(-1, -1));
148  break;
149  }
150  case opencv_apps::Smoothing_Gaussian_Blur:
151  {
153  ROS_DEBUG_STREAM("Applying Gaussian blur with kernel size " << i);
154  cv::GaussianBlur(in_image, out_image, cv::Size(i, i), 0, 0);
155  break;
156  }
157  case opencv_apps::Smoothing_Median_Blur:
158  {
160  ROS_DEBUG_STREAM("Applying Median blur with kernel size " << i);
161  cv::medianBlur(in_image, out_image, i);
162  break;
163  }
164  case opencv_apps::Smoothing_Bilateral_Filter:
165  {
167  ROS_DEBUG_STREAM("Applying Bilateral blur with kernel size " << i);
168  cv::bilateralFilter(in_image, out_image, i, i * 2, i / 2);
169  break;
170  }
171  }
172 
173  //-- Show what you got
174  if (debug_view_)
175  {
176  cv::imshow(window_name_, out_image);
177  int c = cv::waitKey(1);
178  }
179 
180  // Publish the image.
181  sensor_msgs::Image::Ptr out_img = cv_bridge::CvImage(msg->header, "bgr8", out_image).toImageMsg();
182  img_pub_.publish(out_img);
183  }
184  catch (cv::Exception& e)
185  {
186  NODELET_ERROR("Image processing error: %s %s %s %i", e.err.c_str(), e.func.c_str(), e.file.c_str(), e.line);
187  }
188 
189  prev_stamp_ = msg->header.stamp;
190  }
191 
192  void subscribe() // NOLINT(modernize-use-override)
193  {
194  NODELET_DEBUG("Subscribing to image topic.");
195  if (config_.use_camera_info)
196  cam_sub_ = it_->subscribeCamera("image", queue_size_, &SmoothingNodelet::imageCallbackWithInfo, this);
197  else
198  img_sub_ = it_->subscribe("image", queue_size_, &SmoothingNodelet::imageCallback, this);
199  }
200 
201  void unsubscribe() // NOLINT(modernize-use-override)
202  {
203  NODELET_DEBUG("Unsubscribing from image topic.");
204  img_sub_.shutdown();
205  cam_sub_.shutdown();
206  }
207 
208 public:
209  virtual void onInit() // NOLINT(modernize-use-override)
210  {
211  Nodelet::onInit();
213 
214  pnh_->param("queue_size", queue_size_, 3);
215  pnh_->param("debug_view", debug_view_, false);
216  if (debug_view_)
217  {
218  always_subscribe_ = true;
219  }
220  prev_stamp_ = ros::Time(0, 0);
221 
222  window_name_ = "Smoothing Demo";
223  kernel_size_ = 7;
224 
225  reconfigure_server_ = boost::make_shared<dynamic_reconfigure::Server<Config> >(*pnh_);
226  dynamic_reconfigure::Server<Config>::CallbackType f =
228  reconfigure_server_->setCallback(f);
229 
230  img_pub_ = advertiseImage(*pnh_, "image", 1);
231 
233  }
234 };
236 } // namespace opencv_apps
237 
238 namespace smoothing
239 {
241 {
242 public:
243  virtual void onInit() // NOLINT(modernize-use-override)
244  {
245  ROS_WARN("DeprecationWarning: Nodelet smoothing/smoothing is deprecated, "
246  "and renamed to opencv_apps/smoothing.");
248  }
249 };
250 } // namespace smoothing
251 
252 #ifdef USE_PLUGINLIB_CLASS_LIST_MACROS_H
254 #else
256 #endif
smoothing::SmoothingNodelet
Definition: smoothing_nodelet.cpp:240
opencv_apps::SmoothingNodelet::debug_view_
bool debug_view_
Definition: smoothing_nodelet.cpp:79
nodelet.h
opencv_apps::SmoothingNodelet::imageCallbackWithInfo
void imageCallbackWithInfo(const sensor_msgs::ImageConstPtr &msg, const sensor_msgs::CameraInfoConstPtr &cam_info)
Definition: smoothing_nodelet.cpp:100
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
ros::Publisher
image_encodings.h
image_transport::ImageTransport
boost::shared_ptr< image_transport::ImageTransport >
cv_bridge::CvImage::toImageMsg
sensor_msgs::ImagePtr toImageMsg() const
opencv_apps::SmoothingNodelet::img_pub_
image_transport::Publisher img_pub_
Definition: smoothing_nodelet.cpp:66
ros.h
opencv_apps::SmoothingNodelet::kernel_size_
int kernel_size_
Definition: smoothing_nodelet.cpp:85
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::SmoothingNodelet::Config
opencv_apps::SmoothingConfig Config
Definition: smoothing_nodelet.cpp:73
MAX_KERNEL_LENGTH
int MAX_KERNEL_LENGTH
Global Variables.
Definition: smoothing_nodelet.cpp:60
ROS_DEBUG_STREAM
#define ROS_DEBUG_STREAM(args)
opencv_apps::SmoothingNodelet::reconfigureCallback
void reconfigureCallback(Config &new_config, uint32_t level)
Definition: smoothing_nodelet.cpp:87
opencv_apps::SmoothingNodelet::reconfigure_server_
boost::shared_ptr< ReconfigureServer > reconfigure_server_
Definition: smoothing_nodelet.cpp:76
f
f
image_transport::Subscriber
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::SmoothingNodelet::queue_size_
int queue_size_
Definition: smoothing_nodelet.cpp:78
opencv_apps::SmoothingNodelet::onInit
virtual void onInit()
Initialize nodehandles nh_ and pnh_. Subclass should call this method in its onInit method.
Definition: smoothing_nodelet.cpp:209
smoothing::SmoothingNodelet::onInit
virtual void onInit()
Initialize nodehandles nh_ and pnh_. Subclass should call this method in its onInit method.
Definition: smoothing_nodelet.cpp:243
opencv_apps::SmoothingNodelet::unsubscribe
void unsubscribe()
This method is called when publisher is unsubscribed by other nodes. Shut down subscribers in this me...
Definition: smoothing_nodelet.cpp:201
opencv_apps::SmoothingNodelet::imageCallback
void imageCallback(const sensor_msgs::ImageConstPtr &msg)
Definition: smoothing_nodelet.cpp:105
image_transport::CameraSubscriber
opencv_apps::SmoothingNodelet::doWork
void doWork(const sensor_msgs::ImageConstPtr &msg, const std::string &input_frame_from_msg)
Definition: smoothing_nodelet.cpp:115
image_transport::CameraSubscriber::shutdown
void shutdown()
PLUGINLIB_EXPORT_CLASS
PLUGINLIB_EXPORT_CLASS(opencv_apps::SmoothingNodelet, nodelet::Nodelet)
boost::placeholders::_2
boost::arg< 2 > _2
Definition: nodelet.cpp:45
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(...)
image_transport::Publisher::publish
void publish(const sensor_msgs::Image &message) const
opencv_apps
Demo code to calculate moments.
Definition: nodelet.h:68
image_transport.h
opencv_apps::SmoothingNodelet::it_
boost::shared_ptr< image_transport::ImageTransport > it_
Definition: smoothing_nodelet.cpp:71
opencv_apps::SmoothingNodelet::msg_pub_
ros::Publisher msg_pub_
Definition: smoothing_nodelet.cpp:69
nodelet::Nodelet
ros::Time
opencv_apps::SmoothingNodelet::ReconfigureServer
dynamic_reconfigure::Server< Config > ReconfigureServer
Definition: smoothing_nodelet.cpp:74
opencv_apps::SmoothingNodelet::config_
Config config_
Definition: smoothing_nodelet.cpp:75
image_transport::Publisher
opencv_apps::SmoothingNodelet::subscribe
void subscribe()
This method is called when publisher is subscribed by other nodes. Set up subscribers in this method.
Definition: smoothing_nodelet.cpp:192
opencv_apps::SmoothingNodelet::trackbarCallback
static void trackbarCallback(int, void *)
Definition: smoothing_nodelet.cpp:110
opencv_apps::SmoothingNodelet::cam_sub_
image_transport::CameraSubscriber cam_sub_
Definition: smoothing_nodelet.cpp:68
cv_bridge.h
opencv_apps::SmoothingNodelet
Definition: smoothing_nodelet.cpp:64
opencv_apps::SmoothingNodelet::img_sub_
image_transport::Subscriber img_sub_
Definition: smoothing_nodelet.cpp:67
cv_bridge::CvImage
class_list_macros.hpp
opencv_apps::SmoothingNodelet::frameWithDefault
const std::string & frameWithDefault(const std::string &frame, const std::string &image_frame)
Definition: smoothing_nodelet.cpp:93
opencv_apps::SmoothingNodelet::window_name_
std::string window_name_
Definition: smoothing_nodelet.cpp:82
sensor_msgs::image_encodings::BGR8
const std::string BGR8
opencv_apps::SmoothingNodelet::prev_stamp_
ros::Time prev_stamp_
Definition: smoothing_nodelet.cpp:80
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::Nodelet::nh_
boost::shared_ptr< ros::NodeHandle > nh_
Shared pointer to nodehandle.
Definition: nodelet.h:272
smoothing
Definition: smoothing_nodelet.cpp:238
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::SmoothingNodelet::need_config_update_
static bool need_config_update_
Definition: smoothing_nodelet.cpp:83
NODELET_DEBUG
#define NODELET_DEBUG(...)
image_transport::Subscriber::shutdown
void shutdown()


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