00001 #include <ros/ros.h>
00002 #include <geometry_msgs/PolygonStamped.h>
00003 #include <dynamic_reconfigure/server.h>
00004 #include <jsk_perception/camshiftdemoConfig.h>
00005 #include <jsk_perception/RotatedRectStamped.h>
00006 #include <sensor_msgs/SetCameraInfo.h>
00007
00008
00009
00010 #include <sensor_msgs/Image.h>
00011 #include <sensor_msgs/fill_image.h>
00012
00013 #include <image_transport/image_transport.h>
00014 #include <cv_bridge/cv_bridge.h>
00015
00016 #include <opencv2/video/tracking.hpp>
00017 #include <opencv2/imgproc/imgproc.hpp>
00018 #include <opencv2/highgui/highgui.hpp>
00019
00020 #include <iostream>
00021 #include <ctype.h>
00022
00023 using namespace cv;
00024 using namespace std;
00025
00026 class CamShiftDemo
00027 {
00028 protected:
00029 ros::NodeHandle nh_;
00030 image_transport::ImageTransport it_;
00031 image_transport::Subscriber sub_;
00032 image_transport::Publisher pub_, pub_hist_;
00033 sensor_msgs::Image img_;
00034 ros::Subscriber sub_rectangle_;
00035 ros::Publisher pub_result_;
00036 ros::ServiceServer roi_service_;
00037 int max_queue_size_;
00038 bool debug_;
00039
00040 typedef jsk_perception::camshiftdemoConfig Config;
00041 typedef dynamic_reconfigure::Server<Config> ReconfigureServer;
00042 ReconfigureServer reconfigure_server_;
00043 Config config_;
00044
00045 Mat image_;
00046 Mat hsv_, hue_, mask_, histimg_, backproj_;
00047
00048
00049
00050 #if (CV_MAJOR_VERSION == 2 && CV_MINOR_VERSION < 2)
00051 MatND hist_;
00052 #else
00053 Mat hist_;
00054 #endif
00055
00056 bool backprojMode_;
00057 bool selectObject_;
00058 int trackObject_;
00059 bool showHist_;
00060 Point origin_;
00061 Rect selection_;
00062 int vmin_, vmax_, smin_;
00063
00064 Rect trackWindow_;
00065 RotatedRect trackBox_;
00066 int hsize_;
00067 float hranges_[2];
00068 const float* phranges_;
00069
00070 typedef struct {
00071 Mat *image;
00072 bool *selectObject;
00073 int *trackObject;
00074 Rect *selection;
00075 Point *origin;
00076 } on_mouse_param_type;
00077 on_mouse_param_type on_mouse_param_;
00078
00079 public:
00080 CamShiftDemo(ros::NodeHandle nh)
00081 : it_(nh)
00082 {
00083
00084 ros::NodeHandle local_nh("~");
00085 local_nh.param("max_queue_size", max_queue_size_, 3);
00086 local_nh.param("debug", debug_, true);
00087
00088 image_transport::ImageTransport it(nh);
00089 sub_ = it.subscribe(nh.resolveName("image"), 1, &CamShiftDemo::imageCB, this);
00090 pub_ = it.advertise(local_nh.resolveName("image"), 1);
00091 pub_hist_ = it.advertise(local_nh.resolveName("histimg"), 1);
00092
00093 sub_rectangle_ = nh.subscribe(nh.resolveName("screenrectangle"), 1, &CamShiftDemo::setRectangleCB, this);
00094 pub_result_ = nh.advertise<jsk_perception::RotatedRectStamped>(local_nh.resolveName("result"), 1);
00095
00096
00097 roi_service_ = local_nh.advertiseService("set_roi", &CamShiftDemo::setROICb, this);
00098
00099
00100 backprojMode_ = false;
00101 selectObject_ = false;
00102 trackObject_ = 0;
00103 showHist_ = true;
00104 vmin_ = 10; vmax_ = 256; smin_ = 30;
00105
00106 hsize_ = 16;
00107 hranges_[0] = 0; hranges_[1] = 180;
00108 phranges_ = hranges_;
00109
00110
00111 config_.vmin = vmin_;
00112 config_.vmax = vmax_;
00113 config_.smin = smin_;
00114 ReconfigureServer::CallbackType f = boost::bind(&CamShiftDemo::configCb, this, _1, _2);
00115 reconfigure_server_.setCallback(f);
00116
00117
00118 on_mouse_param_.image = &image_;
00119 on_mouse_param_.selectObject = &selectObject_;
00120 on_mouse_param_.trackObject = &trackObject_;
00121 on_mouse_param_.selection = &selection_;
00122 on_mouse_param_.origin = &origin_;
00123
00124 if ( debug_ )
00125 {
00126 namedWindow( "Histogram", 1 );
00127 namedWindow( "CamShift Demo", 1 );
00128
00129 setMouseCallback( "CamShift Demo", onMouse, (void *)&on_mouse_param_ );
00130 createTrackbar( "Vmin", "CamShift Demo", &vmin_, 256, 0 );
00131 createTrackbar( "Vmax", "CamShift Demo", &vmax_, 256, 0 );
00132 createTrackbar( "Smin", "CamShift Demo", &smin_, 256, 0 );
00133
00134 histimg_ = Mat::zeros(200, 320, CV_8UC3);
00135 }
00136
00137 if ( ! debug_ )
00138 {
00139 startWindowThread();
00140 }
00141 }
00142
00143 ~CamShiftDemo()
00144 {
00145 }
00146
00147 bool setROICb(sensor_msgs::SetCameraInfo::Request &req,
00148 sensor_msgs::SetCameraInfo::Response &res)
00149 {
00150
00151 onMouse(CV_EVENT_LBUTTONDOWN,
00152 req.camera_info.roi.x_offset,
00153 req.camera_info.roi.y_offset,
00154 0,
00155 &on_mouse_param_);
00156 onMouse(CV_EVENT_LBUTTONUP,
00157 req.camera_info.roi.x_offset + req.camera_info.roi.width,
00158 req.camera_info.roi.y_offset + req.camera_info.roi.height,
00159 0,
00160 &on_mouse_param_);
00161 res.success = true;
00162 return true;
00163 }
00164
00165 void imageCB(const sensor_msgs::ImageConstPtr& msg_ptr)
00166 {
00167 cv_bridge::CvImagePtr cv_ptr;
00168 Mat frame;
00169
00170 try
00171 {
00172 cv_ptr = cv_bridge::toCvCopy(msg_ptr, "bgr8");
00173 frame = cv_ptr->image;
00174 }
00175 catch (cv_bridge::Exception error)
00176 {
00177 ROS_ERROR("error");
00178 }
00179
00180 frame.copyTo(image_);
00181 cvtColor(image_, hsv_, CV_BGR2HSV);
00182
00183 if( trackObject_ )
00184 {
00185 int _vmin = vmin_, _vmax = vmax_;
00186
00187 inRange(hsv_, Scalar(0, smin_, MIN(_vmin,_vmax)),
00188 Scalar(180, 256, MAX(_vmin, _vmax)), mask_);
00189 int ch[] = {0, 0};
00190 hue_.create(hsv_.size(), hsv_.depth());
00191 mixChannels(&hsv_, 1, &hue_, 1, ch, 1);
00192
00193 if( trackObject_ < 0 )
00194 {
00195 Mat roi(hue_, selection_), maskroi(mask_, selection_);
00196 calcHist(&roi, 1, 0, maskroi, hist_, 1, &hsize_, &phranges_);
00197 normalize(hist_, hist_, 0, 255, CV_MINMAX);
00198
00199 trackWindow_ = selection_;
00200 trackObject_ = 1;
00201
00202 histimg_ = Scalar::all(0);
00203 int binW = histimg_.cols / hsize_;
00204 Mat buf(1, hsize_, CV_8UC3);
00205 for( int i = 0; i < hsize_; i++ )
00206 buf.at<Vec3b>(i) = Vec3b(saturate_cast<uchar>(i*180./hsize_), 255, 255);
00207 cvtColor(buf, buf, CV_HSV2BGR);
00208
00209 for( int i = 0; i < hsize_; i++ )
00210 {
00211 int val = saturate_cast<int>(hist_.at<float>(i)*histimg_.rows/255);
00212 rectangle( histimg_, Point(i*binW,histimg_.rows),
00213 Point((i+1)*binW,histimg_.rows - val),
00214 Scalar(buf.at<Vec3b>(i)), -1, 8 );
00215 }
00216 }
00217
00218 try {
00219 calcBackProject(&hue_, 1, 0, hist_, backproj_, &phranges_);
00220 backproj_ &= mask_;
00221 trackBox_ = CamShift(backproj_, trackWindow_,
00222 TermCriteria( CV_TERMCRIT_EPS | CV_TERMCRIT_ITER, 10, 1 ));
00223
00224 if( backprojMode_ )
00225 cvtColor( backproj_, image_, CV_GRAY2BGR );
00226 ellipse( image_, trackBox_, Scalar(0,0,255), 3, CV_AA );
00227
00228 jsk_perception::RotatedRectStamped result_msg;
00229 result_msg.header = msg_ptr->header;
00230 result_msg.rect.x = trackBox_.center.x;
00231 result_msg.rect.y = trackBox_.center.y;
00232 result_msg.rect.width = trackBox_.size.width;
00233 result_msg.rect.height = trackBox_.size.height;
00234 result_msg.rect.angle = trackBox_.angle;
00235 pub_result_.publish(result_msg);
00236
00237 } catch (...) {
00238 ROS_WARN("illegal tracBox = x:%f y:%f width:%f height:%f angle:%f",
00239 trackBox_.center.x, trackBox_.center.y,
00240 trackBox_.size.width, trackBox_.size.height,
00241 trackBox_.angle);
00242 }
00243 }
00244
00245 if( selectObject_ && selection_.width > 0 && selection_.height > 0 )
00246 {
00247 Mat roi(image_, selection_);
00248 bitwise_not(roi, roi);
00249 }
00250
00251 img_.header = msg_ptr->header;
00252 fillImage(img_, "bgr8", image_.rows, image_.cols, image_.step, const_cast<uint8_t*>(image_.data));
00253 pub_.publish(img_);
00254 fillImage(img_, "bgr8", histimg_.rows, histimg_.cols, histimg_.step, const_cast<uint8_t*>(histimg_.data));
00255 pub_hist_.publish(img_);
00256
00257 if ( debug_ )
00258 {
00259 imshow( "CamShift Demo", image_ );
00260 imshow( "Histogram", histimg_ );
00261
00262 char c = (char)waitKey(10);
00263 switch(c)
00264 {
00265 case 'b':
00266 backprojMode_ = !backprojMode_;
00267 break;
00268 case 'c':
00269 trackObject_ = 0;
00270 histimg_ = Scalar::all(0);
00271 break;
00272 case 'h':
00273 showHist_ = !showHist_;
00274 if( !showHist_ )
00275 destroyWindow( "Histogram" );
00276 else
00277 namedWindow( "Histogram", 1 );
00278 break;
00279 default:
00280 ;
00281 }
00282 }
00283 }
00284
00285 void setRectangleCB(const geometry_msgs::PolygonStampedConstPtr& msg_ptr)
00286 {
00287 selection_.x = msg_ptr->polygon.points[0].x;
00288 selection_.y = msg_ptr->polygon.points[0].y;
00289 selection_.width = msg_ptr->polygon.points[1].x - msg_ptr->polygon.points[0].x;
00290 selection_.height = msg_ptr->polygon.points[1].y - msg_ptr->polygon.points[0].y;
00291 selection_ &= Rect(0, 0, image_.cols, image_.rows);
00292 trackObject_ = -1;
00293 }
00294
00295 void configCb(Config &config, uint32_t level)
00296 {
00297 config_ = config;
00298 vmin_ = config_.vmin;
00299 vmax_ = config_.vmax;
00300 smin_ = config_.smin;
00301 switch ( config_.display_mode )
00302 {
00303 case jsk_perception::camshiftdemo_RGB:
00304 backprojMode_ = false;
00305 break;
00306 case jsk_perception::camshiftdemo_Backproject:
00307 backprojMode_ = true;
00308 break;
00309 }
00310 }
00311
00312
00313 static void onMouse( int event, int x, int y, int flags, void* param)
00314 {
00315 on_mouse_param_type* on_mouse_param = (on_mouse_param_type *)param;
00316 Mat* image = on_mouse_param->image;
00317 bool *selectObject = on_mouse_param->selectObject;
00318 int *trackObject = on_mouse_param->trackObject;
00319 Rect *selection = on_mouse_param->selection;
00320 Point *origin = on_mouse_param->origin;
00321
00322 if( *selectObject )
00323 {
00324 selection->x = MIN(x, origin->x);
00325 selection->y = MIN(y, origin->y);
00326 selection->width = std::abs(x - origin->x);
00327 selection->height = std::abs(y - origin->y);
00328
00329 *selection &= Rect(0, 0, image->cols, image->rows);
00330 }
00331
00332 switch( event )
00333 {
00334 case CV_EVENT_LBUTTONDOWN:
00335 *origin = Point(x,y);
00336 *selection = Rect(x,y,0,0);
00337 *selectObject = true;
00338 break;
00339 case CV_EVENT_LBUTTONUP:
00340 *selectObject = false;
00341 if( selection->width > 0 && selection->height > 0 )
00342 *trackObject = -1;
00343 break;
00344 }
00345 }
00346
00347 };
00348
00349
00350 int main(int argc, char** argv)
00351 {
00352 ros::init(argc, argv, "camshiftdemo");
00353 ros::NodeHandle n;
00354 if (n.resolveName("image") == "/image") {
00355 ROS_WARN("%s: image has not been remapped! Typical command-line usage:\n"
00356 "\t$ ./%s image:=<image topic>", argv[0], argv[0]);
00357 }
00358
00359 CamShiftDemo c(n);
00360
00361 ros::spin();
00362
00363 return 0;
00364 }