00001
00002
00003
00004
00005
00006
00007
00008
00009
00010
00011
00012
00013
00014
00015
00016
00017
00018
00019
00020
00021
00022
00023
00024
00025
00026
00027
00028
00029
00030
00031
00032
00033
00034
00035
00040 #include <ros/ros.h>
00041 #include "opencv_apps/nodelet.h"
00042 #include <image_transport/image_transport.h>
00043 #include <sensor_msgs/image_encodings.h>
00044 #include <cv_bridge/cv_bridge.h>
00045 #include <sensor_msgs/image_encodings.h>
00046
00047 #include <opencv2/highgui/highgui.hpp>
00048 #include <opencv2/imgproc/imgproc.hpp>
00049 #include <opencv2/video/tracking.hpp>
00050
00051 #include <dynamic_reconfigure/server.h>
00052 #include "std_srvs/Empty.h"
00053 #include "opencv_apps/LKFlowConfig.h"
00054 #include "opencv_apps/FlowArrayStamped.h"
00055
00056 namespace opencv_apps
00057 {
00058 class LKFlowNodelet : public opencv_apps::Nodelet
00059 {
00060 image_transport::Publisher img_pub_;
00061 image_transport::Subscriber img_sub_;
00062 image_transport::CameraSubscriber cam_sub_;
00063 ros::Publisher msg_pub_;
00064 ros::ServiceServer initialize_points_service_;
00065 ros::ServiceServer delete_points_service_;
00066 ros::ServiceServer toggle_night_mode_service_;
00067
00068 boost::shared_ptr<image_transport::ImageTransport> it_;
00069
00070 typedef opencv_apps::LKFlowConfig Config;
00071 typedef dynamic_reconfigure::Server<Config> ReconfigureServer;
00072 Config config_;
00073 boost::shared_ptr<ReconfigureServer> reconfigure_server_;
00074
00075 int queue_size_;
00076 bool debug_view_;
00077 ros::Time prev_stamp_;
00078
00079 std::string window_name_;
00080 static bool need_config_update_;
00081
00082 int MAX_COUNT;
00083 bool needToInit;
00084 bool nightMode;
00085 cv::Point2f point;
00086 bool addRemovePt;
00087 cv::Mat gray, prevGray;
00088 std::vector<cv::Point2f> points[2];
00089
00090 float quality_level_;
00091 int min_distance_;
00092 int block_size_;
00093 float harris_k_;
00094
00095 void reconfigureCallback(Config& new_config, uint32_t level)
00096 {
00097 config_ = new_config;
00098 quality_level_ = config_.quality_level;
00099 min_distance_ = config_.min_distance;
00100 block_size_ = config_.block_size;
00101 harris_k_ = config_.harris_k;
00102 }
00103
00104 const std::string& frameWithDefault(const std::string& frame, const std::string& image_frame)
00105 {
00106 if (frame.empty())
00107 return image_frame;
00108 return frame;
00109 }
00110
00111 void imageCallbackWithInfo(const sensor_msgs::ImageConstPtr& msg, const sensor_msgs::CameraInfoConstPtr& cam_info)
00112 {
00113 doWork(msg, cam_info->header.frame_id);
00114 }
00115
00116 void imageCallback(const sensor_msgs::ImageConstPtr& msg)
00117 {
00118 doWork(msg, msg->header.frame_id);
00119 }
00120 #if 0
00121 static void onMouse( int event, int x, int y, int , void* )
00122 {
00123 if( event == CV_EVENT_LBUTTONDOWN )
00124 {
00125 point = Point2f((float)x, (float)y);
00126 addRemovePt = true;
00127 }
00128 }
00129 #endif
00130 static void trackbarCallback(int , void* )
00131 {
00132 need_config_update_ = true;
00133 }
00134
00135 void doWork(const sensor_msgs::ImageConstPtr& msg, const std::string& input_frame_from_msg)
00136 {
00137
00138 try
00139 {
00140
00141 cv::Mat image = cv_bridge::toCvShare(msg, sensor_msgs::image_encodings::BGR8)->image;
00142
00143
00144 opencv_apps::FlowArrayStamped flows_msg;
00145 flows_msg.header = msg->header;
00146
00147 if (debug_view_)
00148 {
00150 cv::namedWindow(window_name_, cv::WINDOW_AUTOSIZE);
00151
00152 cv::createTrackbar("Min Distance", window_name_, &min_distance_, 100, trackbarCallback);
00153 cv::createTrackbar("Block Size", window_name_, &block_size_, 100, trackbarCallback);
00154
00155
00156 if (need_config_update_)
00157 {
00158 reconfigure_server_->updateConfig(config_);
00159 config_.quality_level = quality_level_;
00160 config_.min_distance = min_distance_;
00161 config_.block_size = block_size_;
00162 config_.harris_k = harris_k_;
00163 need_config_update_ = false;
00164 }
00165 }
00166
00167
00168 cv::TermCriteria termcrit(cv::TermCriteria::MAX_ITER + cv::TermCriteria::EPS, 20, 0.03);
00169 cv::Size sub_pix_win_size(10, 10), win_size(31, 31);
00170
00171 if (image.channels() > 1)
00172 {
00173 cv::cvtColor(image, gray, cv::COLOR_BGR2GRAY);
00174 }
00175 else
00176 {
00177 image.copyTo(gray);
00178 }
00179
00180 if (nightMode)
00181 image = cv::Scalar::all(0);
00182
00183 if (needToInit)
00184 {
00185
00186 cv::goodFeaturesToTrack(gray, points[1], MAX_COUNT, quality_level_, min_distance_, cv::Mat(), block_size_,
00187 false, harris_k_);
00188 cv::cornerSubPix(gray, points[1], sub_pix_win_size, cv::Size(-1, -1), termcrit);
00189 addRemovePt = false;
00190 }
00191 else if (!points[0].empty())
00192 {
00193 std::vector<uchar> status;
00194 std::vector<float> err;
00195 if (prevGray.empty())
00196 gray.copyTo(prevGray);
00197 cv::calcOpticalFlowPyrLK(prevGray, gray, points[0], points[1], status, err, win_size, 3, termcrit, 0, 0.001);
00198 size_t i, k;
00199 for (i = k = 0; i < points[1].size(); i++)
00200 {
00201 if (addRemovePt)
00202 {
00203 if (cv::norm(point - points[1][i]) <= 5)
00204 {
00205 addRemovePt = false;
00206 continue;
00207 }
00208 }
00209
00210 if (!status[i])
00211 continue;
00212
00213 points[1][k++] = points[1][i];
00214 cv::circle(image, points[1][i], 3, cv::Scalar(0, 255, 0), -1, 8);
00215 cv::line(image, points[1][i], points[0][i], cv::Scalar(0, 255, 0), 1, 8, 0);
00216
00217 opencv_apps::Flow flow_msg;
00218 opencv_apps::Point2D point_msg;
00219 opencv_apps::Point2D velocity_msg;
00220 point_msg.x = points[1][i].x;
00221 point_msg.y = points[1][i].y;
00222 velocity_msg.x = points[1][i].x - points[0][i].x;
00223 velocity_msg.y = points[1][i].y - points[0][i].y;
00224 flow_msg.point = point_msg;
00225 flow_msg.velocity = velocity_msg;
00226 flows_msg.flow.push_back(flow_msg);
00227 }
00228 points[1].resize(k);
00229 }
00230
00231 if (addRemovePt && points[1].size() < (size_t)MAX_COUNT)
00232 {
00233 std::vector<cv::Point2f> tmp;
00234 tmp.push_back(point);
00235 cv::cornerSubPix(gray, tmp, win_size, cv::Size(-1, -1), termcrit);
00236 points[1].push_back(tmp[0]);
00237 addRemovePt = false;
00238 }
00239
00240 needToInit = false;
00241 if (debug_view_)
00242 {
00243 cv::imshow(window_name_, image);
00244
00245 char c = (char)cv::waitKey(1);
00246
00247
00248 switch (c)
00249 {
00250 case 'r':
00251 needToInit = true;
00252 break;
00253 case 'c':
00254 points[0].clear();
00255 points[1].clear();
00256 break;
00257 case 'n':
00258 nightMode = !nightMode;
00259 break;
00260 }
00261 }
00262 std::swap(points[1], points[0]);
00263 cv::swap(prevGray, gray);
00264
00265
00266 sensor_msgs::Image::Ptr out_img = cv_bridge::CvImage(msg->header, msg->encoding, image).toImageMsg();
00267 img_pub_.publish(out_img);
00268 msg_pub_.publish(flows_msg);
00269 }
00270 catch (cv::Exception& e)
00271 {
00272 NODELET_ERROR("Image processing error: %s %s %s %i", e.err.c_str(), e.func.c_str(), e.file.c_str(), e.line);
00273 }
00274
00275 prev_stamp_ = msg->header.stamp;
00276 }
00277
00278 bool initializePointsCb(std_srvs::Empty::Request& request, std_srvs::Empty::Response& response)
00279 {
00280 needToInit = true;
00281 return true;
00282 }
00283
00284 bool deletePointsCb(std_srvs::Empty::Request& request, std_srvs::Empty::Response& response)
00285 {
00286 points[0].clear();
00287 points[1].clear();
00288 return true;
00289 }
00290
00291 bool toggleNightModeCb(std_srvs::Empty::Request& request, std_srvs::Empty::Response& response)
00292 {
00293 nightMode = !nightMode;
00294 return true;
00295 }
00296
00297 void subscribe()
00298 {
00299 NODELET_DEBUG("Subscribing to image topic.");
00300 if (config_.use_camera_info)
00301 cam_sub_ = it_->subscribeCamera("image", queue_size_, &LKFlowNodelet::imageCallbackWithInfo, this);
00302 else
00303 img_sub_ = it_->subscribe("image", queue_size_, &LKFlowNodelet::imageCallback, this);
00304 }
00305
00306 void unsubscribe()
00307 {
00308 NODELET_DEBUG("Unsubscribing from image topic.");
00309 img_sub_.shutdown();
00310 cam_sub_.shutdown();
00311 }
00312
00313 public:
00314 virtual void onInit()
00315 {
00316 Nodelet::onInit();
00317 it_ = boost::shared_ptr<image_transport::ImageTransport>(new image_transport::ImageTransport(*nh_));
00318
00319 pnh_->param("queue_size", queue_size_, 3);
00320 pnh_->param("debug_view", debug_view_, false);
00321 if (debug_view_)
00322 {
00323 always_subscribe_ = true;
00324 }
00325 prev_stamp_ = ros::Time(0, 0);
00326
00327 window_name_ = "LK Demo";
00328 MAX_COUNT = 500;
00329 needToInit = true;
00330 nightMode = false;
00331 addRemovePt = false;
00332
00333 reconfigure_server_ = boost::make_shared<dynamic_reconfigure::Server<Config> >(*pnh_);
00334 dynamic_reconfigure::Server<Config>::CallbackType f =
00335 boost::bind(&LKFlowNodelet::reconfigureCallback, this, _1, _2);
00336 reconfigure_server_->setCallback(f);
00337
00338 img_pub_ = advertiseImage(*pnh_, "image", 1);
00339 msg_pub_ = advertise<opencv_apps::FlowArrayStamped>(*pnh_, "flows", 1);
00340 initialize_points_service_ = pnh_->advertiseService("initialize_points", &LKFlowNodelet::initializePointsCb, this);
00341 delete_points_service_ = pnh_->advertiseService("delete_points", &LKFlowNodelet::deletePointsCb, this);
00342 toggle_night_mode_service_ = pnh_->advertiseService("toggle_night_mode", &LKFlowNodelet::toggleNightModeCb, this);
00343
00344 NODELET_INFO("Hot keys: ");
00345 NODELET_INFO("\tESC - quit the program");
00346 NODELET_INFO("\tr - auto-initialize tracking");
00347 NODELET_INFO("\tc - delete all the points");
00348 NODELET_INFO("\tn - switch the \"night\" mode on/off");
00349
00350
00351 onInitPostProcess();
00352 }
00353 };
00354 bool LKFlowNodelet::need_config_update_ = false;
00355 }
00356
00357 namespace lk_flow
00358 {
00359 class LKFlowNodelet : public opencv_apps::LKFlowNodelet
00360 {
00361 public:
00362 virtual void onInit()
00363 {
00364 ROS_WARN("DeprecationWarning: Nodelet lk_flow/lk_flow is deprecated, "
00365 "and renamed to opencv_apps/lk_flow.");
00366 opencv_apps::LKFlowNodelet::onInit();
00367 }
00368 };
00369 }
00370
00371 #include <pluginlib/class_list_macros.h>
00372 PLUGINLIB_EXPORT_CLASS(opencv_apps::LKFlowNodelet, nodelet::Nodelet);
00373 PLUGINLIB_EXPORT_CLASS(lk_flow::LKFlowNodelet, nodelet::Nodelet);