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>
53 #include <dynamic_reconfigure/server.h>
54 #include "opencv_apps/SimpleFlowConfig.h"
55 #include "opencv_apps/FlowArrayStamped.h"
68 typedef opencv_apps::SimpleFlowConfig
Config;
90 const std::string&
frameWithDefault(
const std::string& frame,
const std::string& image_frame)
97 void imageCallbackWithInfo(
const sensor_msgs::ImageConstPtr& msg,
const sensor_msgs::CameraInfoConstPtr& cam_info)
99 doWork(msg, cam_info->header.frame_id);
104 doWork(msg, msg->header.frame_id);
112 void doWork(
const sensor_msgs::ImageConstPtr& msg,
const std::string& input_frame_from_msg)
122 if (frame_src.channels() > 1)
128 cv::cvtColor(frame_src, frame, cv::COLOR_GRAY2BGR);
131 cv::resize(frame,
color, cv::Size(frame.cols / (
double)MAX(1,
scale_), frame.rows / (
double)MAX(1,
scale_)), 0, 0,
142 if (frame.type() != CV_8UC3)
147 opencv_apps::FlowArrayStamped flows_msg;
148 flows_msg.header = msg->header;
165 float start = (float)cv::getTickCount();
166 #if CV_MAJOR_VERSION >= 3
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());
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;
180 for (
int i = 0; i < rows; ++i)
182 for (
int j = 0; j < cols; ++j)
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);
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.status.push_back(
true);
199 flows_msg.flow.push_back(flow_msg);
211 int c = cv::waitKey(1);
220 catch (cv::Exception& e)
222 NODELET_ERROR(
"Image processing error: %s %s %s %i", e.err.c_str(), e.func.c_str(), e.file.c_str(), e.line);
262 dynamic_reconfigure::Server<Config>::CallbackType
f =
267 msg_pub_ = advertise<opencv_apps::FlowArrayStamped>(*
pnh_,
"flows", 1);
282 ROS_WARN(
"DeprecationWarning: Nodelet simple_flow/simple_flow is deprecated, "
283 "and renamed to opencv_apps/simple_flow.");
289 #ifdef USE_PLUGINLIB_CLASS_LIST_MACROS_H