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 lk_flow {
00057 class LKFlowNodelet : public opencv_apps::Nodelet
00058 {
00059 image_transport::Publisher img_pub_;
00060 image_transport::Subscriber img_sub_;
00061 image_transport::CameraSubscriber cam_sub_;
00062 ros::Publisher msg_pub_;
00063 ros::ServiceServer initialize_points_service_;
00064 ros::ServiceServer delete_points_service_;
00065 ros::ServiceServer toggle_night_mode_service_;
00066
00067 boost::shared_ptr<image_transport::ImageTransport> it_;
00068
00069 typedef lk_flow::LKFlowConfig Config;
00070 typedef dynamic_reconfigure::Server<Config> ReconfigureServer;
00071 Config config_;
00072 boost::shared_ptr<ReconfigureServer> reconfigure_server_;
00073
00074 bool debug_view_;
00075 ros::Time prev_stamp_;
00076
00077 std::string window_name_;
00078 static bool need_config_update_;
00079
00080 int MAX_COUNT;
00081 bool needToInit;
00082 bool nightMode;
00083 cv::Point2f point;
00084 bool addRemovePt;
00085 cv::Mat gray, prevGray;
00086 std::vector<cv::Point2f> points[2];
00087
00088 void reconfigureCallback(Config &new_config, uint32_t level)
00089 {
00090 config_ = new_config;
00091 }
00092
00093 const std::string &frameWithDefault(const std::string &frame, const std::string &image_frame)
00094 {
00095 if (frame.empty())
00096 return image_frame;
00097 return frame;
00098 }
00099
00100 void imageCallbackWithInfo(const sensor_msgs::ImageConstPtr& msg, const sensor_msgs::CameraInfoConstPtr& cam_info)
00101 {
00102 do_work(msg, cam_info->header.frame_id);
00103 }
00104
00105 void imageCallback(const sensor_msgs::ImageConstPtr& msg)
00106 {
00107 do_work(msg, msg->header.frame_id);
00108 }
00109 #if 0
00110 static void onMouse( int event, int x, int y, int , void* )
00111 {
00112 if( event == CV_EVENT_LBUTTONDOWN )
00113 {
00114 point = Point2f((float)x, (float)y);
00115 addRemovePt = true;
00116 }
00117 }
00118 #endif
00119 static void trackbarCallback( int, void* )
00120 {
00121 need_config_update_ = true;
00122 }
00123
00124 void do_work(const sensor_msgs::ImageConstPtr& msg, const std::string input_frame_from_msg)
00125 {
00126
00127 try
00128 {
00129
00130 cv::Mat image = cv_bridge::toCvShare(msg, sensor_msgs::image_encodings::BGR8)->image;
00131
00132
00133 opencv_apps::FlowArrayStamped flows_msg;
00134 flows_msg.header = msg->header;
00135
00136 if( debug_view_) {
00138 cv::namedWindow( window_name_, cv::WINDOW_AUTOSIZE );
00139
00140 if (need_config_update_) {
00141 reconfigure_server_->updateConfig(config_);
00142 need_config_update_ = false;
00143 }
00144 }
00145
00146
00147 cv::TermCriteria termcrit(cv::TermCriteria::MAX_ITER + cv::TermCriteria::EPS, 20, 0.03);
00148 cv::Size subPixWinSize(10,10), winSize(31,31);
00149
00150 if ( image.channels() > 1 ) {
00151 cv::cvtColor( image, gray, cv::COLOR_BGR2GRAY );
00152 } else {
00153 image.copyTo(gray);
00154 }
00155
00156 if( nightMode )
00157 image = cv::Scalar::all(0);
00158
00159 if( needToInit )
00160 {
00161
00162 cv::goodFeaturesToTrack(gray, points[1], MAX_COUNT, 0.01, 10, cv::Mat(), 3, 0, 0.04);
00163 cv::cornerSubPix(gray, points[1], subPixWinSize, cv::Size(-1,-1), termcrit);
00164 addRemovePt = false;
00165 }
00166 else if( !points[0].empty() )
00167 {
00168 std::vector<uchar> status;
00169 std::vector<float> err;
00170 if(prevGray.empty())
00171 gray.copyTo(prevGray);
00172 cv::calcOpticalFlowPyrLK(prevGray, gray, points[0], points[1], status, err, winSize,
00173 3, termcrit, 0, 0.001);
00174 size_t i, k;
00175 for( i = k = 0; i < points[1].size(); i++ )
00176 {
00177 if( addRemovePt )
00178 {
00179 if( cv::norm(point - points[1][i]) <= 5 )
00180 {
00181 addRemovePt = false;
00182 continue;
00183 }
00184 }
00185
00186 if( !status[i] )
00187 continue;
00188
00189 points[1][k++] = points[1][i];
00190 cv::circle( image, points[1][i], 3, cv::Scalar(0,255,0), -1, 8);
00191 cv::line( image, points[1][i], points[0][i], cv::Scalar(0,255,0), 1, 8, 0);
00192
00193 opencv_apps::Flow flow_msg;
00194 opencv_apps::Point2D point_msg;
00195 opencv_apps::Point2D velocity_msg;
00196 point_msg.x = points[1][i].x;
00197 point_msg.y = points[1][i].y;
00198 velocity_msg.x = points[1][i].x-points[0][i].x;
00199 velocity_msg.y = points[1][i].y-points[0][i].y;
00200 flow_msg.point = point_msg;
00201 flow_msg.velocity = velocity_msg;
00202 flows_msg.flow.push_back(flow_msg);
00203 }
00204 points[1].resize(k);
00205 }
00206
00207 if( addRemovePt && points[1].size() < (size_t)MAX_COUNT )
00208 {
00209 std::vector<cv::Point2f> tmp;
00210 tmp.push_back(point);
00211 cv::cornerSubPix( gray, tmp, winSize, cv::Size(-1,-1), termcrit);
00212 points[1].push_back(tmp[0]);
00213 addRemovePt = false;
00214 }
00215
00216 needToInit = false;
00217 if( debug_view_) {
00218
00219 cv::imshow(window_name_, image);
00220
00221 char c = (char)cv::waitKey(1);
00222
00223
00224 switch( c )
00225 {
00226 case 'r':
00227 needToInit = true;
00228 break;
00229 case 'c':
00230 points[0].clear();
00231 points[1].clear();
00232 break;
00233 case 'n':
00234 nightMode = !nightMode;
00235 break;
00236 }
00237 }
00238 std::swap(points[1], points[0]);
00239 cv::swap(prevGray, gray);
00240
00241
00242 sensor_msgs::Image::Ptr out_img = cv_bridge::CvImage(msg->header, msg->encoding, image).toImageMsg();
00243 img_pub_.publish(out_img);
00244 msg_pub_.publish(flows_msg);
00245 }
00246 catch (cv::Exception &e)
00247 {
00248 NODELET_ERROR("Image processing error: %s %s %s %i", e.err.c_str(), e.func.c_str(), e.file.c_str(), e.line);
00249 }
00250
00251 prev_stamp_ = msg->header.stamp;
00252 }
00253
00254 bool initialize_points_cb(std_srvs::Empty::Request& request, std_srvs::Empty::Response& response) {
00255 needToInit = true;
00256 return true;
00257 }
00258
00259 bool delete_points_cb(std_srvs::Empty::Request& request, std_srvs::Empty::Response& response) {
00260 points[0].clear();
00261 points[1].clear();
00262 return true;
00263 }
00264
00265 bool toggle_night_mode_cb(std_srvs::Empty::Request& request, std_srvs::Empty::Response& response) {
00266 nightMode = !nightMode;
00267 return true;
00268 }
00269
00270 void subscribe()
00271 {
00272 NODELET_DEBUG("Subscribing to image topic.");
00273 if (config_.use_camera_info)
00274 cam_sub_ = it_->subscribeCamera("image", 3, &LKFlowNodelet::imageCallbackWithInfo, this);
00275 else
00276 img_sub_ = it_->subscribe("image", 3, &LKFlowNodelet::imageCallback, this);
00277 }
00278
00279 void unsubscribe()
00280 {
00281 NODELET_DEBUG("Unsubscribing from image topic.");
00282 img_sub_.shutdown();
00283 cam_sub_.shutdown();
00284 }
00285
00286 public:
00287 virtual void onInit()
00288 {
00289 Nodelet::onInit();
00290 it_ = boost::shared_ptr<image_transport::ImageTransport>(new image_transport::ImageTransport(*nh_));
00291
00292 pnh_->param("debug_view", debug_view_, false);
00293 if (debug_view_) {
00294 always_subscribe_ = true;
00295 }
00296 prev_stamp_ = ros::Time(0, 0);
00297
00298 window_name_ = "LK Demo";
00299 MAX_COUNT = 500;
00300 needToInit = true;
00301 nightMode = false;
00302 addRemovePt = false;
00303
00304 reconfigure_server_ = boost::make_shared<dynamic_reconfigure::Server<Config> >(*pnh_);
00305 dynamic_reconfigure::Server<Config>::CallbackType f =
00306 boost::bind(&LKFlowNodelet::reconfigureCallback, this, _1, _2);
00307 reconfigure_server_->setCallback(f);
00308
00309 img_pub_ = advertiseImage(*pnh_, "image", 1);
00310 msg_pub_ = advertise<opencv_apps::FlowArrayStamped>(*pnh_, "flows", 1);
00311 initialize_points_service_ = pnh_->advertiseService("initialize_points", &LKFlowNodelet::initialize_points_cb, this);
00312 delete_points_service_ = pnh_->advertiseService("delete_points", &LKFlowNodelet::delete_points_cb, this);
00313 toggle_night_mode_service_ = pnh_->advertiseService("toggle_night_mode", &LKFlowNodelet::toggle_night_mode_cb, this);
00314
00315
00316 NODELET_INFO("Hot keys: ");
00317 NODELET_INFO("\tESC - quit the program");
00318 NODELET_INFO("\tr - auto-initialize tracking");
00319 NODELET_INFO("\tc - delete all the points");
00320 NODELET_INFO("\tn - switch the \"night\" mode on/off");
00321
00322
00323 onInitPostProcess();
00324 }
00325 };
00326 bool LKFlowNodelet::need_config_update_ = false;
00327 }
00328
00329 #include <pluginlib/class_list_macros.h>
00330 PLUGINLIB_EXPORT_CLASS(lk_flow::LKFlowNodelet, nodelet::Nodelet);