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;
98 quality_level_ = config_.quality_level;
99 min_distance_ = config_.min_distance;
100 block_size_ = config_.block_size;
101 harris_k_ = config_.harris_k;
104 const std::string&
frameWithDefault(
const std::string& frame,
const std::string& image_frame)
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);
132 need_config_update_ =
true;
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;
150 cv::namedWindow(window_name_, cv::WINDOW_AUTOSIZE);
152 cv::createTrackbar(
"Min Distance", window_name_, &min_distance_, 100,
trackbarCallback);
153 cv::createTrackbar(
"Block Size", window_name_, &block_size_, 100,
trackbarCallback);
156 if (need_config_update_)
158 reconfigure_server_->updateConfig(config_);
163 need_config_update_ =
false;
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);
186 cv::goodFeaturesToTrack(gray, points[1], MAX_COUNT, quality_level_, min_distance_, cv::Mat(), block_size_,
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;
195 if (prevGray.empty())
196 gray.copyTo(prevGray);
197 cv::calcOpticalFlowPyrLK(prevGray, gray, points[0], points[1], status, err, win_size, 3, termcrit, 0, 0.001);
199 for (i = k = 0; i < points[1].size(); i++)
203 if (cv::norm(point - points[1][i]) <= 5)
213 points[1][k++] = points[1][i];
214 cv::circle(image, points[1][i], 3, cv::Scalar(0, 255, 0), -1, 8);
215 cv::line(image, points[1][i], points[0][i], cv::Scalar(0, 255, 0), 1, 8, 0);
217 opencv_apps::Flow flow_msg;
218 opencv_apps::Point2D point_msg;
219 opencv_apps::Point2D velocity_msg;
220 point_msg.x = points[1][i].x;
221 point_msg.y = points[1][i].y;
222 velocity_msg.x = points[1][i].x - points[0][i].x;
223 velocity_msg.y = points[1][i].y - points[0][i].y;
224 flow_msg.point = point_msg;
225 flow_msg.velocity = velocity_msg;
226 flows_msg.flow.push_back(flow_msg);
231 if (addRemovePt && points[1].size() < (
size_t)MAX_COUNT)
233 std::vector<cv::Point2f> tmp;
234 tmp.push_back(point);
235 cv::cornerSubPix(gray, tmp, win_size, cv::Size(-1, -1), termcrit);
236 points[1].push_back(tmp[0]);
243 cv::imshow(window_name_, image);
245 char c = (char)cv::waitKey(1);
262 std::swap(points[1], points[0]);
263 cv::swap(prevGray, gray);
270 catch (cv::Exception& e)
272 NODELET_ERROR(
"Image processing error: %s %s %s %i", e.err.c_str(), e.func.c_str(), e.file.c_str(), e.line);
275 prev_stamp_ = msg->header.stamp;
284 bool deletePointsCb(std_srvs::Empty::Request& request, std_srvs::Empty::Response& response)
300 if (config_.use_camera_info)
319 pnh_->param(
"queue_size", queue_size_, 3);
320 pnh_->param(
"debug_view", debug_view_,
false);
327 window_name_ =
"LK Demo";
333 reconfigure_server_ = boost::make_shared<dynamic_reconfigure::Server<Config> >(*pnh_);
334 dynamic_reconfigure::Server<Config>::CallbackType
f =
336 reconfigure_server_->setCallback(f);
339 msg_pub_ = advertise<opencv_apps::FlowArrayStamped>(*
pnh_,
"flows", 1);
364 ROS_WARN(
"DeprecationWarning: Nodelet lk_flow/lk_flow is deprecated, " 365 "and renamed to opencv_apps/lk_flow.");
void unsubscribe()
This method is called when publisher is unsubscribed by other nodes. Shut down subscribers in this me...
CvImageConstPtr toCvShare(const sensor_msgs::ImageConstPtr &source, const std::string &encoding=std::string())
boost::shared_ptr< ReconfigureServer > reconfigure_server_
#define NODELET_ERROR(...)
std::vector< cv::Point2f > points[2]
void publish(const boost::shared_ptr< M > &message) const
void reconfigureCallback(Config &new_config, uint32_t level)
Nodelet to automatically subscribe/unsubscribe topics according to subscription of advertised topics...
Demo code to calculate moments.
ros::ServiceServer initialize_points_service_
boost::shared_ptr< ros::NodeHandle > pnh_
Shared pointer to private nodehandle.
void doWork(const sensor_msgs::ImageConstPtr &msg, const std::string &input_frame_from_msg)
opencv_apps::LKFlowConfig Config
bool always_subscribe_
A flag to disable watching mechanism and always subscribe input topics. It can be specified via ~alwa...
virtual void onInitPostProcess()
Post processing of initialization of nodelet. You need to call this method in order to use always_sub...
virtual void onInit()
Initialize nodehandles nh_ and pnh_. Subclass should call this method in its onInit method...
void publish(const sensor_msgs::Image &message) const
PLUGINLIB_EXPORT_CLASS(opencv_apps::LKFlowNodelet, nodelet::Nodelet)
const std::string & frameWithDefault(const std::string &frame, const std::string &image_frame)
boost::shared_ptr< ros::NodeHandle > nh_
Shared pointer to nodehandle.
bool deletePointsCb(std_srvs::Empty::Request &request, std_srvs::Empty::Response &response)
bool toggleNightModeCb(std_srvs::Empty::Request &request, std_srvs::Empty::Response &response)
boost::shared_ptr< image_transport::ImageTransport > it_
void imageCallback(const sensor_msgs::ImageConstPtr &msg)
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...
void subscribe()
This method is called when publisher is subscribed by other nodes. Set up subscribers in this method...
image_transport::CameraSubscriber cam_sub_
#define NODELET_INFO(...)
ros::ServiceServer toggle_night_mode_service_
ros::ServiceServer delete_points_service_
image_transport::Publisher img_pub_
dynamic_reconfigure::Server< Config > ReconfigureServer
image_transport::Subscriber img_sub_
bool initializePointsCb(std_srvs::Empty::Request &request, std_srvs::Empty::Response &response)
virtual void onInit()
Initialize nodehandles nh_ and pnh_. Subclass should call this method in its onInit method...
virtual void onInit()
Initialize nodehandles nh_ and pnh_. Subclass should call this method in its onInit method...
#define NODELET_DEBUG(...)
void imageCallbackWithInfo(const sensor_msgs::ImageConstPtr &msg, const sensor_msgs::CameraInfoConstPtr &cam_info)
sensor_msgs::ImagePtr toImageMsg() const
static void trackbarCallback(int, void *)
static bool need_config_update_