corner_harris_nodelet.cpp
Go to the documentation of this file.
1 // -*- coding:utf-8-unix; mode: c++; indent-tabs-mode: nil; c-basic-offset: 2; -*-
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 Kei Okada 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 #include <ros/ros.h>
36 #include "opencv_apps/nodelet.h"
39 #include <cv_bridge/cv_bridge.h>
40 
41 #include <opencv2/highgui/highgui.hpp>
42 #include <opencv2/imgproc/imgproc.hpp>
43 
44 #include <dynamic_reconfigure/server.h>
45 #include "opencv_apps/CornerHarrisConfig.h"
46 
47 // https://github.com/opencv/opencv/blob/master/samples/cpp/tutorial_code/TrackingMotion/cornerHarris_Demo.cpp
54 namespace opencv_apps
55 {
57 {
62 
64 
65  typedef opencv_apps::CornerHarrisConfig Config;
66  typedef dynamic_reconfigure::Server<Config> ReconfigureServer;
67  Config config_;
69 
72 
73  std::string window_name_;
74  static bool need_config_update_;
75 
77 
78  void reconfigureCallback(Config& new_config, uint32_t level)
79  {
80  config_ = new_config;
81  threshold_ = config_.threshold;
82  }
83 
84  const std::string& frameWithDefault(const std::string& frame, const std::string& image_frame)
85  {
86  if (frame.empty())
87  return image_frame;
88  return frame;
89  }
90 
91  void imageCallbackWithInfo(const sensor_msgs::ImageConstPtr& msg, const sensor_msgs::CameraInfoConstPtr& cam_info)
92  {
93  doWork(msg, cam_info->header.frame_id);
94  }
95 
96  void imageCallback(const sensor_msgs::ImageConstPtr& msg)
97  {
98  doWork(msg, msg->header.frame_id);
99  }
100 
101  static void trackbarCallback(int /*unused*/, void* /*unused*/)
102  {
103  need_config_update_ = true;
104  }
105 
106  void doWork(const sensor_msgs::ImageConstPtr& image_msg, const std::string& input_frame_from_msg)
107  {
108  // Work on the image.
109  try
110  {
111  // Convert the image into something opencv can handle.
112  cv::Mat frame = cv_bridge::toCvShare(image_msg, sensor_msgs::image_encodings::BGR8)->image;
113 
114  // Do the work
115  cv::Mat dst, dst_norm, dst_norm_scaled;
116  dst = cv::Mat::zeros(frame.size(), CV_32FC1);
117 
118  cv::Mat src_gray;
119 
120  if (frame.channels() > 1)
121  {
122  cv::cvtColor(frame, src_gray, cv::COLOR_BGR2GRAY);
123  }
124  else
125  {
126  src_gray = frame;
127  cv::cvtColor(src_gray, frame, cv::COLOR_GRAY2BGR);
128  }
129 
131  int block_size = 2;
132  int aperture_size = 3;
133  double k = 0.04;
134 
136  cv::cornerHarris(src_gray, dst, block_size, aperture_size, k, cv::BORDER_DEFAULT);
137 
139  cv::normalize(dst, dst_norm, 0, 255, cv::NORM_MINMAX, CV_32FC1, cv::Mat());
140  cv::convertScaleAbs(dst_norm, dst_norm_scaled);
141 
143  for (int j = 0; j < dst_norm.rows; j++)
144  {
145  for (int i = 0; i < dst_norm.cols; i++)
146  {
147  if ((int)dst_norm.at<float>(j, i) > threshold_)
148  {
149  cv::circle(frame, cv::Point(i, j), 5, cv::Scalar(0), 2, 8, 0);
150  }
151  }
152  }
153 
155  if (debug_view_)
156  {
157  cv::namedWindow(window_name_, cv::WINDOW_AUTOSIZE);
158  const int max_threshold = 255;
159  if (need_config_update_)
160  {
161  config_.threshold = threshold_;
162  reconfigure_server_->updateConfig(config_);
163  need_config_update_ = false;
164  }
165  cv::createTrackbar("Threshold:", window_name_, &threshold_, max_threshold, trackbarCallback);
166  }
167 
168  if (debug_view_)
169  {
170  cv::imshow(window_name_, frame);
171  int c = cv::waitKey(1);
172  }
173 
174  // Publish the image.
175  sensor_msgs::Image::Ptr out_img =
177  img_pub_.publish(out_img);
178  }
179  catch (cv::Exception& e)
180  {
181  NODELET_ERROR("Image processing error: %s %s %s %i", e.err.c_str(), e.func.c_str(), e.file.c_str(), e.line);
182  }
183  }
184 
185  void subscribe() // NOLINT(modernize-use-override)
186  {
187  NODELET_DEBUG("Subscribing to image topic.");
188  if (config_.use_camera_info)
189  cam_sub_ = it_->subscribeCamera("image", queue_size_, &CornerHarrisNodelet::imageCallbackWithInfo, this);
190  else
191  img_sub_ = it_->subscribe("image", queue_size_, &CornerHarrisNodelet::imageCallback, this);
192  }
193 
194  void unsubscribe() // NOLINT(modernize-use-override)
195  {
196  NODELET_DEBUG("Unsubscribing from image topic.");
197  img_sub_.shutdown();
198  cam_sub_.shutdown();
199  }
200 
201 public:
202  virtual void onInit() // NOLINT(modernize-use-override)
203  {
204  Nodelet::onInit();
206 
207  pnh_->param("queue_size", queue_size_, 3);
208  pnh_->param("debug_view", debug_view_, false);
209 
210  if (debug_view_)
211  {
212  always_subscribe_ = true;
213  }
214 
215  window_name_ = "CornerHarris Demo";
216 
217  reconfigure_server_ = boost::make_shared<dynamic_reconfigure::Server<Config> >(*pnh_);
218  dynamic_reconfigure::Server<Config>::CallbackType f =
219  boost::bind(&CornerHarrisNodelet::reconfigureCallback, this, _1, _2);
220  reconfigure_server_->setCallback(f);
221 
222  img_pub_ = advertiseImage(*pnh_, "image", 1);
223 
225  }
226 };
228 } // namespace opencv_apps
229 
230 namespace corner_harris
231 {
233 {
234 public:
235  virtual void onInit() // NOLINT(modernize-use-override)
236  {
237  ROS_WARN("DeprecationWarning: Nodelet corner_harris/corner_harris is deprecated, "
238  "and renamed to opencv_apps/corner_harris.");
240  }
241 };
242 } // namespace corner_harris
243 
CvImageConstPtr toCvShare(const sensor_msgs::ImageConstPtr &source, const std::string &encoding=std::string())
void subscribe()
This method is called when publisher is subscribed by other nodes. Set up subscribers in this method...
#define NODELET_ERROR(...)
void doWork(const sensor_msgs::ImageConstPtr &image_msg, const std::string &input_frame_from_msg)
f
Nodelet to automatically subscribe/unsubscribe topics according to subscription of advertised topics...
Definition: nodelet.h:70
Demo code to calculate moments.
Definition: nodelet.h:48
boost::shared_ptr< ReconfigureServer > reconfigure_server_
boost::shared_ptr< ros::NodeHandle > pnh_
Shared pointer to private nodehandle.
Definition: nodelet.h:250
#define ROS_WARN(...)
void imageCallback(const sensor_msgs::ImageConstPtr &msg)
image_transport::CameraSubscriber cam_sub_
bool always_subscribe_
A flag to disable watching mechanism and always subscribe input topics. It can be specified via ~alwa...
Definition: nodelet.h:273
virtual void onInitPostProcess()
Post processing of initialization of nodelet. You need to call this method in order to use always_sub...
Definition: nodelet.cpp:57
virtual void onInit()
Initialize nodehandles nh_ and pnh_. Subclass should call this method in its onInit method...
Definition: nodelet.cpp:40
void publish(const sensor_msgs::Image &message) const
opencv_apps::CornerHarrisConfig Config
image_transport::Publisher img_pub_
image_transport::Subscriber img_sub_
void imageCallbackWithInfo(const sensor_msgs::ImageConstPtr &msg, const sensor_msgs::CameraInfoConstPtr &cam_info)
static void trackbarCallback(int, void *)
dynamic_reconfigure::Server< Config > ReconfigureServer
boost::shared_ptr< ros::NodeHandle > nh_
Shared pointer to nodehandle.
Definition: nodelet.h:245
void reconfigureCallback(Config &new_config, uint32_t level)
void unsubscribe()
This method is called when publisher is unsubscribed by other nodes. Shut down subscribers in this me...
virtual void onInit()
Initialize nodehandles nh_ and pnh_. Subclass should call this method in its onInit method...
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:180
const std::string & frameWithDefault(const std::string &frame, const std::string &image_frame)
boost::shared_ptr< image_transport::ImageTransport > it_
#define NODELET_DEBUG(...)
sensor_msgs::ImagePtr toImageMsg() const
virtual void onInit()
Initialize nodehandles nh_ and pnh_. Subclass should call this method in its onInit method...
PLUGINLIB_EXPORT_CLASS(opencv_apps::CornerHarrisNodelet, nodelet::Nodelet)


opencv_apps
Author(s): Kei Okada
autogenerated on Wed Apr 24 2019 03:00:17