simple_flow_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 // https://github.com/Itseez/opencv/blob/2.4/samples/cpp/simpleflow_demo.cpp
40 #include <ros/ros.h>
41 #include "opencv_apps/nodelet.h"
43 #include <cv_bridge/cv_bridge.h>
45 
46 #include <opencv2/highgui/highgui.hpp>
47 #include <opencv2/imgproc/imgproc.hpp>
48 #include <opencv2/video/tracking.hpp>
49 #if CV_MAJOR_VERSION == 3
50 #include <opencv2/optflow.hpp>
51 #endif
52 
53 #include <dynamic_reconfigure/server.h>
54 #include "opencv_apps/SimpleFlowConfig.h"
55 #include "opencv_apps/FlowArrayStamped.h"
56 
57 namespace opencv_apps
58 {
60 {
65 
67 
68  typedef opencv_apps::SimpleFlowConfig Config;
69  typedef dynamic_reconfigure::Server<Config> ReconfigureServer;
70  Config config_;
72 
77 
78  std::string window_name_;
79  static bool need_config_update_;
80  int scale_;
81 
82  cv::Mat gray, prevGray;
83 
84  void reconfigureCallback(Config& new_config, uint32_t level)
85  {
86  config_ = new_config;
87  scale_ = config_.scale;
88  }
89 
90  const std::string& frameWithDefault(const std::string& frame, const std::string& image_frame)
91  {
92  if (frame.empty())
93  return image_frame;
94  return frame;
95  }
96 
97  void imageCallbackWithInfo(const sensor_msgs::ImageConstPtr& msg, const sensor_msgs::CameraInfoConstPtr& cam_info)
98  {
99  doWork(msg, cam_info->header.frame_id);
100  }
101 
102  void imageCallback(const sensor_msgs::ImageConstPtr& msg)
103  {
104  doWork(msg, msg->header.frame_id);
105  }
106 
107  static void trackbarCallback(int /*unused*/, void* /*unused*/)
108  {
109  need_config_update_ = true;
110  }
111 
112  void doWork(const sensor_msgs::ImageConstPtr& msg, const std::string& input_frame_from_msg)
113  {
114  // Work on the image.
115  try
116  {
117  // Convert the image into something opencv can handle.
118  cv::Mat frame_src = cv_bridge::toCvShare(msg, sensor_msgs::image_encodings::BGR8)->image;
119 
121  cv::Mat frame;
122  if (frame_src.channels() > 1)
123  {
124  frame = frame_src;
125  }
126  else
127  {
128  cv::cvtColor(frame_src, frame, cv::COLOR_GRAY2BGR);
129  }
130 
131  cv::resize(frame, gray, cv::Size(frame.cols / (double)MAX(1, scale_), frame.rows / (double)MAX(1, scale_)), 0, 0,
132  CV_INTER_AREA);
133  if (prevGray.empty())
134  gray.copyTo(prevGray);
135 
136  if (gray.rows != prevGray.rows && gray.cols != prevGray.cols)
137  {
138  NODELET_WARN("Images should be of equal sizes");
139  gray.copyTo(prevGray);
140  }
141 
142  if (frame.type() != 16)
143  {
144  NODELET_ERROR("Images should be of equal type CV_8UC3");
145  }
146  // Messages
147  opencv_apps::FlowArrayStamped flows_msg;
148  flows_msg.header = msg->header;
149 
150  // Do the work
151  cv::Mat flow;
152 
153  if (debug_view_)
154  {
155  cv::namedWindow(window_name_, cv::WINDOW_AUTOSIZE);
156  cv::createTrackbar("Scale", window_name_, &scale_, 24, trackbarCallback);
157  if (need_config_update_)
158  {
159  config_.scale = scale_;
160  reconfigure_server_->updateConfig(config_);
161  need_config_update_ = false;
162  }
163  }
164 
165  float start = (float)cv::getTickCount();
166 #if CV_MAJOR_VERSION == 3
167  cv::optflow::calcOpticalFlowSF(gray, prevGray,
168 #else
169  cv::calcOpticalFlowSF(gray, prevGray,
170 #endif
171  flow, 3, 2, 4, 4.1, 25.5, 18, 55.0, 25.5, 0.35, 18, 55.0, 25.5, 10);
172  NODELET_INFO("calcOpticalFlowSF : %lf sec", (cv::getTickCount() - start) / cv::getTickFrequency());
173 
174  // writeOpticalFlowToFile(flow, file);
175  int cols = flow.cols;
176  int rows = flow.rows;
177  double scale_col = frame.cols / (double)flow.cols;
178  double scale_row = frame.rows / (double)flow.rows;
179 
180  for (int i = 0; i < rows; ++i)
181  {
182  for (int j = 0; j < cols; ++j)
183  {
184  cv::Vec2f flow_at_point = flow.at<cv::Vec2f>(i, j);
185  cv::line(frame, cv::Point(scale_col * j, scale_row * i),
186  cv::Point(scale_col * (j + flow_at_point[0]), scale_row * (i + flow_at_point[1])),
187  cv::Scalar(0, 255, 0), 1, 8, 0);
188 
189  opencv_apps::Flow flow_msg;
190  opencv_apps::Point2D point_msg;
191  opencv_apps::Point2D velocity_msg;
192  point_msg.x = scale_col * j;
193  point_msg.y = scale_row * i;
194  velocity_msg.x = scale_col * flow_at_point[0];
195  velocity_msg.y = scale_row * flow_at_point[1];
196  flow_msg.point = point_msg;
197  flow_msg.velocity = velocity_msg;
198  flows_msg.flow.push_back(flow_msg);
199  }
200  }
201 
202  // cv::cvtColor( frame, src_gray, cv::COLOR_BGR2GRAY );
204  // Canny( src_gray, edges, 50, 200, 3 );
205 
206  //-- Show what you got
207  if (debug_view_)
208  {
209  cv::imshow(window_name_, frame);
210  int c = cv::waitKey(1);
211  }
212 
213  cv::swap(prevGray, gray);
214  // Publish the image.
215  sensor_msgs::Image::Ptr out_img = cv_bridge::CvImage(msg->header, "bgr8", frame).toImageMsg();
216  img_pub_.publish(out_img);
217  msg_pub_.publish(flows_msg);
218  }
219  catch (cv::Exception& e)
220  {
221  NODELET_ERROR("Image processing error: %s %s %s %i", e.err.c_str(), e.func.c_str(), e.file.c_str(), e.line);
222  }
223 
224  prev_stamp_ = msg->header.stamp;
225  }
226 
227  void subscribe() // NOLINT(modernize-use-override)
228  {
229  NODELET_DEBUG("Subscribing to image topic.");
230  if (config_.use_camera_info)
231  cam_sub_ = it_->subscribeCamera("image", queue_size_, &SimpleFlowNodelet::imageCallbackWithInfo, this);
232  else
233  img_sub_ = it_->subscribe("image", queue_size_, &SimpleFlowNodelet::imageCallback, this);
234  }
235 
236  void unsubscribe() // NOLINT(modernize-use-override)
237  {
238  NODELET_DEBUG("Unsubscribing from image topic.");
239  img_sub_.shutdown();
240  cam_sub_.shutdown();
241  }
242 
243 public:
244  virtual void onInit() // NOLINT(modernize-use-override)
245  {
246  Nodelet::onInit();
248 
249  pnh_->param("queue_size", queue_size_, 3);
250  pnh_->param("debug_view", debug_view_, false);
251  if (debug_view_)
252  {
253  always_subscribe_ = true;
254  }
255  prev_stamp_ = ros::Time(0, 0);
256 
257  window_name_ = "simpleflow_demo";
258  scale_ = 4.0;
259 
260  reconfigure_server_ = boost::make_shared<dynamic_reconfigure::Server<Config> >(*pnh_);
261  dynamic_reconfigure::Server<Config>::CallbackType f =
262  boost::bind(&SimpleFlowNodelet::reconfigureCallback, this, _1, _2);
263  reconfigure_server_->setCallback(f);
264 
265  img_pub_ = advertiseImage(*pnh_, "image", 1);
266  msg_pub_ = advertise<opencv_apps::FlowArrayStamped>(*pnh_, "flows", 1);
267 
269  }
270 };
272 } // namespace opencv_apps
273 
274 namespace simple_flow
275 {
277 {
278 public:
279  virtual void onInit() // NOLINT(modernize-use-override)
280  {
281  ROS_WARN("DeprecationWarning: Nodelet simple_flow/simple_flow is deprecated, "
282  "and renamed to opencv_apps/simple_flow.");
284  }
285 };
286 } // namespace simple_flow
287 
CvImageConstPtr toCvShare(const sensor_msgs::ImageConstPtr &source, const std::string &encoding=std::string())
void doWork(const sensor_msgs::ImageConstPtr &msg, const std::string &input_frame_from_msg)
#define NODELET_ERROR(...)
#define NODELET_WARN(...)
image_transport::Publisher img_pub_
void publish(const boost::shared_ptr< M > &message) const
void imageCallback(const sensor_msgs::ImageConstPtr &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
opencv_apps::SimpleFlowConfig Config
PLUGINLIB_EXPORT_CLASS(opencv_apps::SimpleFlowNodelet, nodelet::Nodelet)
void reconfigureCallback(Config &new_config, uint32_t level)
boost::shared_ptr< ros::NodeHandle > pnh_
Shared pointer to private nodehandle.
Definition: nodelet.h:250
#define ROS_WARN(...)
image_transport::CameraSubscriber cam_sub_
virtual void onInit()
Initialize nodehandles nh_ and pnh_. Subclass should call this method in its onInit method...
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
void unsubscribe()
This method is called when publisher is unsubscribed by other nodes. Shut down subscribers in this me...
void subscribe()
This method is called when publisher is subscribed by other nodes. Set up subscribers in this method...
boost::shared_ptr< ros::NodeHandle > nh_
Shared pointer to nodehandle.
Definition: nodelet.h:245
virtual void onInit()
Initialize nodehandles nh_ and pnh_. Subclass should call this method in its onInit method...
dynamic_reconfigure::Server< Config > ReconfigureServer
boost::shared_ptr< ReconfigureServer > reconfigure_server_
const std::string & frameWithDefault(const std::string &frame, const std::string &image_frame)
boost::shared_ptr< image_transport::ImageTransport > it_
void imageCallbackWithInfo(const sensor_msgs::ImageConstPtr &msg, const sensor_msgs::CameraInfoConstPtr &cam_info)
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
#define NODELET_INFO(...)
image_transport::Subscriber img_sub_
static void trackbarCallback(int, void *)
#define NODELET_DEBUG(...)
sensor_msgs::ImagePtr toImageMsg() const


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