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


jsk_perception
Author(s): Manabu Saito
autogenerated on Sat Mar 23 2013 18:21:31