47 #include <opencv2/highgui/highgui.hpp>
48 #include <opencv2/imgproc/imgproc.hpp>
49 #include <opencv2/video/tracking.hpp>
51 #include <dynamic_reconfigure/server.h>
52 #include "opencv_apps/FBackFlowConfig.h"
53 #include "opencv_apps/FlowArrayStamped.h"
66 typedef opencv_apps::FBackFlowConfig
Config;
85 const std::string&
frameWithDefault(
const std::string& frame,
const std::string& image_frame)
92 void imageCallbackWithInfo(
const sensor_msgs::ImageConstPtr& msg,
const sensor_msgs::CameraInfoConstPtr& cam_info)
94 doWork(msg, cam_info->header.frame_id);
99 doWork(msg, msg->header.frame_id);
107 void doWork(
const sensor_msgs::ImageConstPtr& msg,
const std::string& input_frame_from_msg)
116 opencv_apps::FlowArrayStamped flows_msg;
117 flows_msg.header = msg->header;
132 NODELET_WARN_STREAM(
"Detected jump back in time of " << msg->header.stamp <<
". Clearing optical flow cache.");
137 if (frame.channels() > 1)
139 cv::cvtColor(frame,
gray, cv::COLOR_BGR2GRAY);
147 cv::calcOpticalFlowFarneback(
prevgray,
gray,
flow, 0.5, 3, 15, 3, 5, 1.2, 0);
151 cv::Scalar color = cv::Scalar(0, 255, 0);
152 for (
int y = 0; y <
cflow.rows; y += step)
153 for (
int x = 0; x <
cflow.cols; x += step)
155 const cv::Point2f& fxy =
flow.at<cv::Point2f>(y, x);
156 cv::line(
cflow, cv::Point(x, y), cv::Point(cvRound(x + fxy.x), cvRound(y + fxy.y)), color);
157 cv::circle(
cflow, cv::Point(x, y), 2, color, -1);
159 opencv_apps::Flow flow_msg;
160 opencv_apps::Point2D point_msg;
161 opencv_apps::Point2D velocity_msg;
164 velocity_msg.x = fxy.x;
165 velocity_msg.y = fxy.y;
166 flow_msg.point = point_msg;
167 flow_msg.velocity = velocity_msg;
168 flows_msg.status.push_back(
true);
169 flows_msg.flow.push_back(flow_msg);
179 int c = cv::waitKey(1);
187 catch (cv::Exception& e)
189 NODELET_ERROR(
"Image processing error: %s %s %s %i", e.err.c_str(), e.func.c_str(), e.file.c_str(), e.line);
228 dynamic_reconfigure::Server<Config>::CallbackType
f =
233 msg_pub_ = advertise<opencv_apps::FlowArrayStamped>(*
pnh_,
"flows", 1);
248 ROS_WARN(
"DeprecationWarning: Nodelet fback_flow/fback_flow is deprecated, "
249 "and renamed to opencv_apps/fback_flow.");
255 #ifdef USE_PLUGINLIB_CLASS_LIST_MACROS_H