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
00042 #include <ros/ros.h>
00043 #include "opencv_apps/nodelet.h"
00044 #include <image_transport/image_transport.h>
00045 #include <sensor_msgs/image_encodings.h>
00046 #include <cv_bridge/cv_bridge.h>
00047 #include <sensor_msgs/image_encodings.h>
00048
00049 #include <iostream>
00050 #include <ctype.h>
00051 #include <opencv2/video/tracking.hpp>
00052 #include <opencv2/highgui/highgui.hpp>
00053 #include <opencv2/imgproc/imgproc.hpp>
00054
00055 #include <dynamic_reconfigure/server.h>
00056 #include "opencv_apps/CamShiftConfig.h"
00057 #include "opencv_apps/RotatedRectStamped.h"
00058
00059 namespace camshift {
00060 class CamShiftNodelet : public opencv_apps::Nodelet
00061 {
00062 image_transport::Publisher img_pub_, bproj_pub_;
00063 image_transport::Subscriber img_sub_;
00064 image_transport::CameraSubscriber cam_sub_;
00065 ros::Publisher msg_pub_;
00066
00067 boost::shared_ptr<image_transport::ImageTransport> it_;
00068
00069 typedef camshift::CamShiftConfig 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_, histogram_name_;
00078 static bool need_config_update_;
00079 static bool on_mouse_update_;
00080 static int on_mouse_event_;
00081 static int on_mouse_x_;
00082 static int on_mouse_y_;
00083
00084 int vmin_, vmax_, smin_;
00085 bool backprojMode;
00086 bool selectObject;
00087 int trackObject;
00088 bool showHist;
00089 cv::Point origin;
00090 cv::Rect selection;
00091 bool paused;
00092
00093 cv::Rect trackWindow;
00094 int hsize;
00095 float hranges[2];
00096 const float* phranges;
00097 cv::Mat hist, histimg;
00098
00099
00100 static void onMouse( int event, int x, int y, int, void* )
00101 {
00102 on_mouse_update_ = true;
00103 on_mouse_event_ = event;
00104 on_mouse_x_ = x;
00105 on_mouse_y_ = y;
00106 }
00107
00108 void reconfigureCallback(Config &new_config, uint32_t level)
00109 {
00110 config_ = new_config;
00111 vmin_ = config_.vmin;
00112 vmax_ = config_.vmax;
00113 smin_ = config_.smin;
00114 }
00115
00116 const std::string &frameWithDefault(const std::string &frame, const std::string &image_frame)
00117 {
00118 if (frame.empty())
00119 return image_frame;
00120 return frame;
00121 }
00122
00123 void imageCallbackWithInfo(const sensor_msgs::ImageConstPtr& msg, const sensor_msgs::CameraInfoConstPtr& cam_info)
00124 {
00125 do_work(msg, cam_info->header.frame_id);
00126 }
00127
00128 void imageCallback(const sensor_msgs::ImageConstPtr& msg)
00129 {
00130 do_work(msg, msg->header.frame_id);
00131 }
00132
00133 static void trackbarCallback( int, void* )
00134 {
00135 need_config_update_ = true;
00136 }
00137
00138 void do_work(const sensor_msgs::ImageConstPtr& msg, const std::string input_frame_from_msg)
00139 {
00140
00141 try
00142 {
00143
00144 cv::Mat frame = cv_bridge::toCvShare(msg, sensor_msgs::image_encodings::BGR8)->image;
00145 cv::Mat backproj;
00146
00147
00148 opencv_apps::RotatedRectStamped rect_msg;
00149 rect_msg.header = msg->header;
00150
00151
00152
00153 if( debug_view_) {
00155
00156 cv::namedWindow( window_name_, cv::WINDOW_AUTOSIZE );
00157
00158 cv::setMouseCallback( window_name_, onMouse, 0 );
00159 cv::createTrackbar( "Vmin", window_name_, &vmin_, 256, trackbarCallback);
00160 cv::createTrackbar( "Vmax", window_name_, &vmax_, 256, trackbarCallback);
00161 cv::createTrackbar( "Smin", window_name_, &smin_, 256, trackbarCallback);
00162
00163 if (need_config_update_) {
00164 config_.vmin = vmin_;
00165 config_.vmax = vmax_;
00166 config_.smin = smin_;
00167 reconfigure_server_->updateConfig(config_);
00168 need_config_update_ = false;
00169 }
00170 }
00171
00172 if ( on_mouse_update_ ) {
00173 int event = on_mouse_event_;
00174 int x = on_mouse_x_;
00175 int y = on_mouse_y_;
00176
00177 if( selectObject )
00178 {
00179 selection.x = MIN(x, origin.x);
00180 selection.y = MIN(y, origin.y);
00181 selection.width = std::abs(x - origin.x);
00182 selection.height = std::abs(y - origin.y);
00183
00184 selection &= cv::Rect(0, 0, frame.cols, frame.rows);
00185 }
00186
00187 switch( event )
00188 {
00189 case cv::EVENT_LBUTTONDOWN:
00190 origin = cv::Point(x,y);
00191 selection = cv::Rect(x,y,0,0);
00192 selectObject = true;
00193 break;
00194 case cv::EVENT_LBUTTONUP:
00195 selectObject = false;
00196 if( selection.width > 0 && selection.height > 0 )
00197 trackObject = -1;
00198 break;
00199 }
00200 on_mouse_update_ = false;
00201 }
00202
00203 if( !paused )
00204 {
00205 cv::Mat hsv, hue, mask;
00206 cv::cvtColor(frame, hsv, cv::COLOR_BGR2HSV);
00207
00208 if( trackObject )
00209 {
00210 int _vmin = vmin_, _vmax = vmax_;
00211
00212 cv::inRange(hsv, cv::Scalar(0, smin_, MIN(_vmin,_vmax)),
00213 cv::Scalar(180, 256, MAX(_vmin, _vmax)), mask);
00214 int ch[] = {0, 0};
00215 hue.create(hsv.size(), hsv.depth());
00216 cv::mixChannels(&hsv, 1, &hue, 1, ch, 1);
00217
00218 if( trackObject < 0 )
00219 {
00220 cv::Mat roi(hue, selection), maskroi(mask, selection);
00221 cv::calcHist(&roi, 1, 0, maskroi, hist, 1, &hsize, &phranges);
00222 cv::normalize(hist, hist, 0, 255, cv::NORM_MINMAX);
00223 std::vector<float> hist_value;
00224 hist_value.resize(hsize);
00225 for(int i = 0; i < hsize; i ++) { hist_value[i] = hist.at<float>(i);}
00226 pnh_->setParam("histogram", hist_value);
00227
00228 trackWindow = selection;
00229 trackObject = 1;
00230
00231 histimg = cv::Scalar::all(0);
00232 int binW = histimg.cols / hsize;
00233 cv::Mat buf(1, hsize, CV_8UC3);
00234 for( int i = 0; i < hsize; i++ )
00235 buf.at<cv::Vec3b>(i) = cv::Vec3b(cv::saturate_cast<uchar>(i*180./hsize), 255, 255);
00236 cv::cvtColor(buf, buf, cv::COLOR_HSV2BGR);
00237
00238 for( int i = 0; i < hsize; i++ )
00239 {
00240 int val = cv::saturate_cast<int>(hist.at<float>(i)*histimg.rows/255);
00241 cv::rectangle( histimg, cv::Point(i*binW,histimg.rows),
00242 cv::Point((i+1)*binW,histimg.rows - val),
00243 cv::Scalar(buf.at<cv::Vec3b>(i)), -1, 8 );
00244 }
00245 }
00246
00247 cv::calcBackProject(&hue, 1, 0, hist, backproj, &phranges);
00248 backproj &= mask;
00249 cv::RotatedRect trackBox = cv::CamShift(backproj, trackWindow,
00250 cv::TermCriteria( cv::TermCriteria::EPS + cv::TermCriteria::MAX_ITER, 10, 1 ));
00251 if( trackWindow.area() <= 1 )
00252 {
00253 int cols = backproj.cols, rows = backproj.rows, r = (MIN(cols, rows) + 5)/6;
00254
00255
00256 trackWindow = cv::Rect(cols/2 - r, rows/2 - r,
00257 cols/2 + r, rows/2 + r) &
00258 cv::Rect(0, 0, cols, rows);
00259 }
00260
00261 if( backprojMode )
00262 cv::cvtColor( backproj, frame, cv::COLOR_GRAY2BGR );
00263 #ifndef CV_VERSION_EPOCH
00264 cv::ellipse( frame, trackBox, cv::Scalar(0,0,255), 3, cv::LINE_AA );
00265 #else
00266 cv::ellipse( frame, trackBox, cv::Scalar(0,0,255), 3, CV_AA );
00267 #endif
00268
00269 rect_msg.rect.angle = trackBox.angle;
00270 opencv_apps::Point2D point_msg;
00271 opencv_apps::Size size_msg;
00272 point_msg.x = trackBox.center.x;
00273 point_msg.y = trackBox.center.y;
00274 size_msg.width = trackBox.size.width;
00275 size_msg.height = trackBox.size.height;
00276 rect_msg.rect.center = point_msg;
00277 rect_msg.rect.size = size_msg;
00278 }
00279 }
00280 else if( trackObject < 0 )
00281 paused = false;
00282
00283 if( selectObject && selection.width > 0 && selection.height > 0 )
00284 {
00285 cv::Mat roi(frame, selection);
00286 bitwise_not(roi, roi);
00287 }
00288
00289 if( debug_view_ ) {
00290 cv::imshow( window_name_, frame );
00291 cv::imshow( histogram_name_, histimg );
00292
00293 char c = (char)cv::waitKey(1);
00294
00295
00296 switch(c)
00297 {
00298 case 'b':
00299 backprojMode = !backprojMode;
00300 break;
00301 case 'c':
00302 trackObject = 0;
00303 histimg = cv::Scalar::all(0);
00304 break;
00305 case 'h':
00306 showHist = !showHist;
00307 if( !showHist )
00308 cv::destroyWindow( histogram_name_ );
00309 else
00310 cv::namedWindow( histogram_name_, 1 );
00311 break;
00312 case 'p':
00313 paused = !paused;
00314 break;
00315 default:
00316 ;
00317 }
00318 }
00319
00320
00321 sensor_msgs::Image::Ptr out_img1 = cv_bridge::CvImage(msg->header, msg->encoding, frame).toImageMsg();
00322 sensor_msgs::Image::Ptr out_img2 = cv_bridge::CvImage(msg->header, sensor_msgs::image_encodings::MONO8, backproj).toImageMsg();
00323 img_pub_.publish(out_img1);
00324 bproj_pub_.publish(out_img2);
00325 if( trackObject )
00326 msg_pub_.publish(rect_msg);
00327 }
00328 catch (cv::Exception &e)
00329 {
00330 NODELET_ERROR("Image processing error: %s %s %s %i", e.err.c_str(), e.func.c_str(), e.file.c_str(), e.line);
00331 }
00332
00333 prev_stamp_ = msg->header.stamp;
00334 }
00335
00336 void subscribe()
00337 {
00338 NODELET_DEBUG("Subscribing to image topic.");
00339 if (config_.use_camera_info)
00340 cam_sub_ = it_->subscribeCamera("image", 3, &CamShiftNodelet::imageCallbackWithInfo, this);
00341 else
00342 img_sub_ = it_->subscribe("image", 3, &CamShiftNodelet::imageCallback, this);
00343 }
00344
00345 void unsubscribe()
00346 {
00347 NODELET_DEBUG("Unsubscribing from image topic.");
00348 img_sub_.shutdown();
00349 cam_sub_.shutdown();
00350 }
00351
00352 public:
00353 virtual void onInit()
00354 {
00355 Nodelet::onInit();
00356 it_ = boost::shared_ptr<image_transport::ImageTransport>(new image_transport::ImageTransport(*nh_));
00357
00358 pnh_->param("debug_view", debug_view_, false);
00359 if (debug_view_) {
00360 always_subscribe_ = true;
00361 }
00362 prev_stamp_ = ros::Time(0, 0);
00363
00364 window_name_ = "CamShift Demo";
00365 histogram_name_ = "Histogram";
00366
00367 vmin_ = 10; vmax_ = 256; smin_ = 30;
00368 backprojMode = false;
00369 selectObject = false;
00370 trackObject = 0;
00371 showHist = true;
00372 paused = false;
00373
00374 hsize = 16;
00375 hranges[0] = 0;
00376 hranges[1] = 180;
00377 phranges = hranges;
00378 histimg = cv::Mat::zeros(200, 320, CV_8UC3);
00379
00380 reconfigure_server_ = boost::make_shared<dynamic_reconfigure::Server<Config> >(*pnh_);
00381 dynamic_reconfigure::Server<Config>::CallbackType f =
00382 boost::bind(&CamShiftNodelet::reconfigureCallback, this, _1, _2);
00383 reconfigure_server_->setCallback(f);
00384
00385
00386 img_pub_ = advertiseImage(*pnh_, "image", 1);
00387 bproj_pub_ = advertiseImage(*pnh_, "back_project", 1);
00388 msg_pub_ = advertise<opencv_apps::RotatedRectStamped>(*pnh_, "track_box", 1);
00389
00390 NODELET_INFO("Hot keys: ");
00391 NODELET_INFO("\tESC - quit the program");
00392 NODELET_INFO("\tc - stop the tracking");
00393 NODELET_INFO("\tb - switch to/from backprojection view");
00394 NODELET_INFO("\th - show/hide object histogram");
00395 NODELET_INFO("\tp - pause video");
00396 NODELET_INFO("To initialize tracking, select the object with mouse");
00397
00398 std::vector<float> hist_value;
00399 pnh_->getParam("histogram", hist_value);
00400 if ( hist_value.size() == hsize ) {
00401 hist.create(hsize, 1, CV_32F);
00402 for(int i = 0; i < hsize; i ++) { hist.at<float>(i) = hist_value[i];}
00403 trackObject = 1;
00404 trackWindow = cv::Rect(0, 0, 640, 480);
00405
00406
00407 histimg = cv::Scalar::all(0);
00408 int binW = histimg.cols / hsize;
00409 cv::Mat buf(1, hsize, CV_8UC3);
00410 for( int i = 0; i < hsize; i++ )
00411 buf.at<cv::Vec3b>(i) = cv::Vec3b(cv::saturate_cast<uchar>(i*180./hsize), 255, 255);
00412 cv::cvtColor(buf, buf, cv::COLOR_HSV2BGR);
00413
00414 for( int i = 0; i < hsize; i++ )
00415 {
00416 int val = cv::saturate_cast<int>(hist.at<float>(i)*histimg.rows/255);
00417 cv::rectangle( histimg, cv::Point(i*binW,histimg.rows),
00418 cv::Point((i+1)*binW,histimg.rows - val),
00419 cv::Scalar(buf.at<cv::Vec3b>(i)), -1, 8 );
00420 }
00421 }
00422 onInitPostProcess();
00423 }
00424 };
00425 bool CamShiftNodelet::need_config_update_ = false;
00426 bool CamShiftNodelet::on_mouse_update_ = false;
00427 int CamShiftNodelet::on_mouse_event_ = 0;
00428 int CamShiftNodelet::on_mouse_x_ = 0;
00429 int CamShiftNodelet::on_mouse_y_ = 0;
00430 }
00431
00432 #include <pluginlib/class_list_macros.h>
00433 PLUGINLIB_EXPORT_CLASS(camshift::CamShiftNodelet, nodelet::Nodelet);