goodfeature_track_nodelet.cpp
Go to the documentation of this file.
1 /*********************************************************************
2 * Software License Agreement (BSD License)
3 *
4 * Copyright (c) 2014, Kei Okada.
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/or other materials provided
16 * with the distribution.
17 * * Neither the name of the Kei Okada 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 // http://github.com/Itseez/opencv/blob/master/samples/cpp/tutorial_code/TrackingMotion/goodFeaturesToTrack_Demo.cpp
42 #include <ros/ros.h>
43 #include "opencv_apps/nodelet.h"
45 #include <cv_bridge/cv_bridge.h>
47 
48 #include <opencv2/highgui/highgui.hpp>
49 #include <opencv2/imgproc/imgproc.hpp>
50 
51 #include <dynamic_reconfigure/server.h>
52 #include "opencv_apps/GoodfeatureTrackConfig.h"
53 #include "opencv_apps/Point2D.h"
54 #include "opencv_apps/Point2DArrayStamped.h"
55 
56 namespace opencv_apps
57 {
59 {
64 
66 
67  typedef opencv_apps::GoodfeatureTrackConfig Config;
68  typedef dynamic_reconfigure::Server<Config> ReconfigureServer;
69  Config config_;
71 
75 
76  std::string window_name_;
77  static bool need_config_update_;
78 
80 
81  void reconfigureCallback(Config& new_config, uint32_t level)
82  {
83  config_ = new_config;
84  max_corners_ = config_.max_corners;
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  static void trackbarCallback(int /*unused*/, void* /*unused*/)
105  {
106  need_config_update_ = true;
107  }
108 
109  void doWork(const sensor_msgs::ImageConstPtr& msg, const std::string& input_frame_from_msg)
110  {
111  // Work on the image.
112  try
113  {
114  // Convert the image into something opencv can handle.
115  cv::Mat frame = cv_bridge::toCvShare(msg, sensor_msgs::image_encodings::BGR8)->image;
116 
117  // Messages
118  opencv_apps::Point2DArrayStamped corners_msg;
119  corners_msg.header = msg->header;
120 
121  // Do the work
122  cv::Mat src_gray;
123  int max_trackbar = 100;
124 
125  if (frame.channels() > 1)
126  {
127  cv::cvtColor(frame, src_gray, cv::COLOR_BGR2GRAY);
128  }
129  else
130  {
131  src_gray = frame;
132  cv::cvtColor(src_gray, frame, cv::COLOR_GRAY2BGR);
133  }
134 
135  if (debug_view_)
136  {
138  cv::namedWindow(window_name_, cv::WINDOW_AUTOSIZE);
139  cv::createTrackbar("Max corners", window_name_, &max_corners_, max_trackbar, trackbarCallback);
140  if (need_config_update_)
141  {
142  config_.max_corners = max_corners_;
143  reconfigure_server_->updateConfig(config_);
144  need_config_update_ = false;
145  }
146  }
147 
149  if (max_corners_ < 1)
150  {
151  max_corners_ = 1;
152  }
153 
155  std::vector<cv::Point2f> corners;
156  double quality_level = 0.01;
157  double min_distance = 10;
158  int block_size = 3;
159  bool use_harris_detector = false;
160  double k = 0.04;
161 
162  cv::RNG rng(12345);
163 
165  cv::goodFeaturesToTrack(src_gray, corners, max_corners_, quality_level, min_distance, cv::Mat(), block_size,
166  use_harris_detector, k);
167 
169  NODELET_INFO_STREAM("** Number of corners detected: " << corners.size());
170  int r = 4;
171  for (const cv::Point2f& corner : corners)
172  {
173  cv::circle(frame, corner, r, cv::Scalar(rng.uniform(0, 255), rng.uniform(0, 255), rng.uniform(0, 255)), -1, 8,
174  0);
175  }
176 
177  //-- Show what you got
178  if (debug_view_)
179  {
180  cv::imshow(window_name_, frame);
181  int c = cv::waitKey(1);
182  }
183 
184  // Create msgs
185  for (const cv::Point2f& i : corners)
186  {
187  opencv_apps::Point2D corner;
188  corner.x = i.x;
189  corner.y = i.y;
190  corners_msg.points.push_back(corner);
191  }
192  // Publish the image.
193  sensor_msgs::Image::Ptr out_img = cv_bridge::CvImage(msg->header, "bgr8", frame).toImageMsg();
194  img_pub_.publish(out_img);
195  msg_pub_.publish(corners_msg);
196  }
197  catch (cv::Exception& e)
198  {
199  NODELET_ERROR("Image processing error: %s %s %s %i", e.err.c_str(), e.func.c_str(), e.file.c_str(), e.line);
200  }
201 
202  prev_stamp_ = msg->header.stamp;
203  }
204 
205  void subscribe() // NOLINT(modernize-use-override)
206  {
207  NODELET_DEBUG("Subscribing to image topic.");
208  if (config_.use_camera_info)
209  cam_sub_ = it_->subscribeCamera("image", queue_size_, &GoodfeatureTrackNodelet::imageCallbackWithInfo, this);
210  else
211  img_sub_ = it_->subscribe("image", queue_size_, &GoodfeatureTrackNodelet::imageCallback, this);
212  }
213 
214  void unsubscribe() // NOLINT(modernize-use-override)
215  {
216  NODELET_DEBUG("Unsubscribing from image topic.");
217  img_sub_.shutdown();
218  cam_sub_.shutdown();
219  }
220 
221 public:
222  virtual void onInit() // NOLINT(modernize-use-override)
223  {
224  Nodelet::onInit();
226 
227  pnh_->param("queue_size", queue_size_, 3);
228  pnh_->param("debug_view", debug_view_, false);
229  if (debug_view_)
230  {
231  always_subscribe_ = true;
232  }
233  prev_stamp_ = ros::Time(0, 0);
234 
235  window_name_ = "Image";
236  max_corners_ = 23;
237 
238  reconfigure_server_ = boost::make_shared<dynamic_reconfigure::Server<Config> >(*pnh_);
239  dynamic_reconfigure::Server<Config>::CallbackType f =
240  boost::bind(&GoodfeatureTrackNodelet::reconfigureCallback, this, _1, _2);
241  reconfigure_server_->setCallback(f);
242 
243  img_pub_ = advertiseImage(*pnh_, "image", 1);
244  msg_pub_ = advertise<opencv_apps::Point2DArrayStamped>(*pnh_, "corners", 1);
245 
247  }
248 };
250 } // namespace opencv_apps
251 
253 {
255 {
256 public:
257  virtual void onInit() // NOLINT(modernize-use-override)
258  {
259  ROS_WARN("DeprecationWarning: Nodelet goodfeature_track/goodfeature_track is deprecated, "
260  "and renamed to opencv_apps/goodfeature_track.");
262  }
263 };
264 } // namespace goodfeature_track
265 
CvImageConstPtr toCvShare(const sensor_msgs::ImageConstPtr &source, const std::string &encoding=std::string())
#define NODELET_INFO_STREAM(...)
#define NODELET_ERROR(...)
void publish(const boost::shared_ptr< M > &message) const
PLUGINLIB_EXPORT_CLASS(opencv_apps::GoodfeatureTrackNodelet, nodelet::Nodelet)
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
void imageCallbackWithInfo(const sensor_msgs::ImageConstPtr &msg, const sensor_msgs::CameraInfoConstPtr &cam_info)
boost::shared_ptr< ros::NodeHandle > pnh_
Shared pointer to private nodehandle.
Definition: nodelet.h:250
#define ROS_WARN(...)
void subscribe()
This method is called when publisher is subscribed by other nodes. Set up subscribers in this method...
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...
bool always_subscribe_
A flag to disable watching mechanism and always subscribe input topics. It can be specified via ~alwa...
Definition: nodelet.h:273
const std::string & frameWithDefault(const std::string &frame, const std::string &image_frame)
image_transport::CameraSubscriber cam_sub_
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
boost::shared_ptr< ros::NodeHandle > nh_
Shared pointer to nodehandle.
Definition: nodelet.h:245
boost::shared_ptr< ReconfigureServer > reconfigure_server_
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
dynamic_reconfigure::Server< Config > ReconfigureServer
void doWork(const sensor_msgs::ImageConstPtr &msg, const std::string &input_frame_from_msg)
virtual void onInit()
Initialize nodehandles nh_ and pnh_. Subclass should call this method in its onInit method...
opencv_apps::GoodfeatureTrackConfig Config
#define NODELET_DEBUG(...)
boost::shared_ptr< image_transport::ImageTransport > it_
sensor_msgs::ImagePtr toImageMsg() const
void imageCallback(const sensor_msgs::ImageConstPtr &msg)


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