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 "std_srvs/Empty.h"
53 #include "opencv_apps/LKFlowConfig.h"
54 #include "opencv_apps/FlowArrayStamped.h"
70 typedef opencv_apps::LKFlowConfig
Config;
88 std::vector<cv::Point2f>
points[2];
104 const std::string&
frameWithDefault(
const std::string& frame,
const std::string& image_frame)
111 void imageCallbackWithInfo(
const sensor_msgs::ImageConstPtr& msg,
const sensor_msgs::CameraInfoConstPtr& cam_info)
113 doWork(msg, cam_info->header.frame_id);
118 doWork(msg, msg->header.frame_id);
121 static void onMouse(
int event,
int x,
int y,
int ,
void* )
123 if( event == CV_EVENT_LBUTTONDOWN )
125 point = Point2f((
float)x, (
float)y);
135 void doWork(
const sensor_msgs::ImageConstPtr& msg,
const std::string& input_frame_from_msg)
144 opencv_apps::FlowArrayStamped flows_msg;
145 flows_msg.header = msg->header;
168 cv::TermCriteria termcrit(cv::TermCriteria::MAX_ITER + cv::TermCriteria::EPS, 20, 0.03);
169 cv::Size sub_pix_win_size(10, 10), win_size(31, 31);
171 if (image.channels() > 1)
173 cv::cvtColor(image,
gray, cv::COLOR_BGR2GRAY);
181 image = cv::Scalar::all(0);
188 cv::cornerSubPix(
gray,
points[1], sub_pix_win_size, cv::Size(-1, -1), termcrit);
191 else if (!
points[0].empty())
193 std::vector<uchar> status;
194 std::vector<float> err;
197 cv::calcOpticalFlowPyrLK(
prevGray,
gray,
points[0],
points[1], status, err, win_size, 3, termcrit, 0, 0.001);
210 opencv_apps::Flow flow_msg;
211 opencv_apps::Point2D point_msg;
212 opencv_apps::Point2D velocity_msg;
215 cv::circle(image,
points[1][i], 3, cv::Scalar(0, 255, 0), -1, 8);
216 cv::line(image,
points[1][i],
points[0][i], cv::Scalar(0, 255, 0), 1, 8, 0);
217 point_msg.x =
points[1][i].x;
218 point_msg.y =
points[1][i].y;
222 flow_msg.point = point_msg;
223 flow_msg.velocity = velocity_msg;
224 flows_msg.status.push_back(status[i]);
225 flows_msg.flow.push_back(flow_msg);
231 std::vector<cv::Point2f> tmp;
232 tmp.push_back(
point);
233 cv::cornerSubPix(
gray, tmp, win_size, cv::Size(-1, -1), termcrit);
234 points[1].push_back(tmp[0]);
243 char c = (char)cv::waitKey(1);
268 catch (cv::Exception& e)
270 NODELET_ERROR(
"Image processing error: %s %s %s %i", e.err.c_str(), e.func.c_str(), e.file.c_str(), e.line);
276 bool initializePointsCb(std_srvs::Empty::Request& request, std_srvs::Empty::Response& response)
282 bool deletePointsCb(std_srvs::Empty::Request& request, std_srvs::Empty::Response& response)
289 bool toggleNightModeCb(std_srvs::Empty::Request& request, std_srvs::Empty::Response& response)
332 dynamic_reconfigure::Server<Config>::CallbackType
f =
337 msg_pub_ = advertise<opencv_apps::FlowArrayStamped>(*
pnh_,
"flows", 1);
362 ROS_WARN(
"DeprecationWarning: Nodelet lk_flow/lk_flow is deprecated, "
363 "and renamed to opencv_apps/lk_flow.");
369 #ifdef USE_PLUGINLIB_CLASS_LIST_MACROS_H