morphology_nodelet.cpp
Go to the documentation of this file.
1 // -*- mode: c++ -*-
2 /*********************************************************************
3  * Software License Agreement (BSD License)
4  *
5  * Copyright (c) 2022, 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://docs.opencv.org/3.4/d3/dbe/tutorial_opening_closing_hats.html
37 // https://github.com/opencv/opencv/blob/2.4/samples/cpp/tutorial_code/ImgProc/Morphology_2.cpp
44 #include <ros/ros.h>
45 #include "opencv_apps/nodelet.h"
48 #include <cv_bridge/cv_bridge.h>
49 
50 #include <iostream>
51 #include <vector>
52 
53 #include "opencv2/imgproc/imgproc.hpp"
54 #include "opencv2/highgui/highgui.hpp"
55 #include "opencv2/features2d/features2d.hpp"
56 
57 #include <dynamic_reconfigure/server.h>
58 #include "opencv_apps/MorphologyConfig.h"
59 
60 namespace opencv_apps
61 {
63 {
68 
70 
71  typedef opencv_apps::MorphologyConfig Config;
72  typedef dynamic_reconfigure::Server<Config> ReconfigureServer;
73  Config config_;
75 
79 
80  std::string window_name_;
81 
82  void reconfigureCallback(Config& new_config, uint32_t level)
83  {
84  config_ = new_config;
85  }
86 
87  const std::string& frameWithDefault(const std::string& frame, const std::string& image_frame)
88  {
89  if (frame.empty())
90  return image_frame;
91  return frame;
92  }
93 
94  void imageCallbackWithInfo(const sensor_msgs::ImageConstPtr& msg, const sensor_msgs::CameraInfoConstPtr& cam_info)
95  {
96  doWork(msg, cam_info->header.frame_id);
97  }
98 
99  void imageCallback(const sensor_msgs::ImageConstPtr& msg)
100  {
101  doWork(msg, msg->header.frame_id);
102  }
103 
104  void doWork(const sensor_msgs::ImageConstPtr& msg, const std::string& input_frame_from_msg)
105  {
106  // Work on the image.
107  try
108  {
109  // Convert the image into something opencv can handle.
110  cv::Mat in_image = cv_bridge::toCvShare(msg, sensor_msgs::image_encodings::BGR8)->image;
111 
112  if (debug_view_)
113  {
114  cv::namedWindow(window_name_, cv::WINDOW_AUTOSIZE);
115  }
116 
117  cv::Mat out_image = in_image.clone();
118 
119  int morph_operator = config_.morph_operator;
120  int morph_element = config_.morph_element;
121  int morph_size = config_.morph_size;
122 
123  ROS_DEBUG_STREAM("Applying morphology transforms with operator " << morph_operator << ", element "
124  << morph_element << ", and size " << morph_size);
125 
126  cv::Mat element = cv::getStructuringElement(morph_element, cv::Size(2 * morph_size + 1, 2 * morph_size + 1),
127  cv::Point(morph_size, morph_size));
128 
129  // Since MORPH_X : 2,3,4,5 and 6
130  cv::morphologyEx(in_image, out_image, morph_operator + 2, element);
131 
132  //-- Show what you got
133  if (debug_view_)
134  {
135  cv::imshow(window_name_, out_image);
136  int c = cv::waitKey(1);
137  }
138 
139  // Publish the image.
140  sensor_msgs::Image::Ptr out_img = cv_bridge::CvImage(msg->header, "bgr8", out_image).toImageMsg();
141  img_pub_.publish(out_img);
142  }
143  catch (cv::Exception& e)
144  {
145  NODELET_ERROR("Image processing error: %s %s %s %i", e.err.c_str(), e.func.c_str(), e.file.c_str(), e.line);
146  }
147 
148  prev_stamp_ = msg->header.stamp;
149  }
150 
151  void subscribe() // NOLINT(modernize-use-override)
152  {
153  NODELET_DEBUG("Subscribing to image topic.");
154  if (config_.use_camera_info)
155  cam_sub_ = it_->subscribeCamera("image", queue_size_, &MorphologyNodelet::imageCallbackWithInfo, this);
156  else
157  img_sub_ = it_->subscribe("image", queue_size_, &MorphologyNodelet::imageCallback, this);
158  }
159 
160  void unsubscribe() // NOLINT(modernize-use-override)
161  {
162  NODELET_DEBUG("Unsubscribing from image topic.");
163  img_sub_.shutdown();
164  cam_sub_.shutdown();
165  }
166 
167 public:
168  virtual void onInit() // NOLINT(modernize-use-override)
169  {
170  Nodelet::onInit();
172 
173  pnh_->param("queue_size", queue_size_, 3);
174  pnh_->param("debug_view", debug_view_, false);
175  if (debug_view_)
176  {
177  always_subscribe_ = true;
178  }
179  prev_stamp_ = ros::Time(0, 0);
180 
181  window_name_ = "Morphology Demo (" + ros::this_node::getName() + ")";
182  reconfigure_server_ = boost::make_shared<dynamic_reconfigure::Server<Config> >(*pnh_);
183  dynamic_reconfigure::Server<Config>::CallbackType f =
185  reconfigure_server_->setCallback(f);
186 
187  img_pub_ = advertiseImage(*pnh_, "image", 1);
188 
190  }
191 };
192 } // namespace opencv_apps
193 
194 namespace morphology
195 {
197 {
198 public:
199  virtual void onInit() // NOLINT(modernize-use-override)
200  {
201  ROS_WARN("DeprecationWarning: Nodelet morphology/morphology is deprecated, "
202  "and renamed to opencv_apps/morphology.");
204  }
205 };
206 } // namespace morphology
207 
208 #ifdef USE_PLUGINLIB_CLASS_LIST_MACROS_H
210 #else
212 #endif
CvImageConstPtr toCvShare(const sensor_msgs::ImageConstPtr &source, const std::string &encoding=std::string())
void imageCallbackWithInfo(const sensor_msgs::ImageConstPtr &msg, const sensor_msgs::CameraInfoConstPtr &cam_info)
#define NODELET_ERROR(...)
virtual void onInit()
Initialize nodehandles nh_ and pnh_. Subclass should call this method in its onInit method...
PLUGINLIB_EXPORT_CLASS(opencv_apps::MorphologyNodelet, nodelet::Nodelet)
dynamic_reconfigure::Server< Config > ReconfigureServer
f
boost::shared_ptr< ReconfigureServer > reconfigure_server_
const std::string & frameWithDefault(const std::string &frame, const std::string &image_frame)
Nodelet to automatically subscribe/unsubscribe topics according to subscription of advertised topics...
Definition: nodelet.h:90
Demo code to calculate moments.
Definition: nodelet.h:68
boost::arg< 2 > _2
Definition: nodelet.cpp:45
ROSCPP_DECL const std::string & getName()
boost::shared_ptr< ros::NodeHandle > pnh_
Shared pointer to private nodehandle.
Definition: nodelet.h:277
void unsubscribe()
This method is called when publisher is unsubscribed by other nodes. Shut down subscribers in this me...
#define ROS_WARN(...)
image_transport::Publisher img_pub_
image_transport::Subscriber img_sub_
void reconfigureCallback(Config &new_config, uint32_t level)
sensor_msgs::ImagePtr toImageMsg() const
bool always_subscribe_
A flag to disable watching mechanism and always subscribe input topics. It can be specified via ~alwa...
Definition: nodelet.h:300
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
virtual void onInit()
Initialize nodehandles nh_ and pnh_. Subclass should call this method in its onInit method...
Definition: nodelet.cpp:60
void subscribe()
This method is called when publisher is subscribed by other nodes. Set up subscribers in this method...
image_transport::CameraSubscriber cam_sub_
boost::shared_ptr< ros::NodeHandle > nh_
Shared pointer to nodehandle.
Definition: nodelet.h:272
boost::arg< 1 > _1
Definition: nodelet.cpp:44
void doWork(const sensor_msgs::ImageConstPtr &msg, const std::string &input_frame_from_msg)
boost::shared_ptr< image_transport::ImageTransport > it_
#define ROS_DEBUG_STREAM(args)
void publish(const sensor_msgs::Image &message) const
void imageCallback(const sensor_msgs::ImageConstPtr &msg)
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
opencv_apps::MorphologyConfig Config
virtual void onInit()
Initialize nodehandles nh_ and pnh_. Subclass should call this method in its onInit method...
#define NODELET_DEBUG(...)


opencv_apps
Author(s): Kei Okada
autogenerated on Thu Feb 2 2023 03:40:24