camshift_nodelet.cpp
Go to the documentation of this file.
00001 /*********************************************************************
00002 * Software License Agreement (BSD License)
00003 *
00004 *  Copyright (c) 2014, Kei Okada.
00005 *  All rights reserved.
00006 *
00007 *  Redistribution and use in source and binary forms, with or without
00008 *  modification, are permitted provided that the following conditions
00009 *  are met:
00010 *
00011 *   * Redistributions of source code must retain the above copyright
00012 *     notice, this list of conditions and the following disclaimer.
00013 *   * Redistributions in binary form must reproduce the above
00014 *     copyright notice, this list of conditions and the following
00015 *     disclaimer in the documentation and/or other materials provided
00016 *     with the distribution.
00017 *   * Neither the name of the Kei Okada nor the names of its
00018 *     contributors may be used to endorse or promote products derived
00019 *     from this software without specific prior written permission.
00020 *
00021 *  THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
00022 *  "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
00023 *  LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
00024 *  FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
00025 *  COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
00026 *  INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
00027 *  BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
00028 *  LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
00029 *  CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
00030 *  LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
00031 *  ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
00032 *  POSSIBILITY OF SUCH DAMAGE.
00033 *********************************************************************/
00034 
00035 // https://github.com/Itseez/opencv/blob/2.4/samples/cpp/camshiftdemo.cpp
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 opencv_apps
00060 {
00061 class CamShiftNodelet : public opencv_apps::Nodelet
00062 {
00063   image_transport::Publisher img_pub_, bproj_pub_;
00064   image_transport::Subscriber img_sub_;
00065   image_transport::CameraSubscriber cam_sub_;
00066   ros::Publisher msg_pub_;
00067 
00068   boost::shared_ptr<image_transport::ImageTransport> it_;
00069 
00070   typedef opencv_apps::CamShiftConfig 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_, histogram_name_;
00080   static bool need_config_update_;
00081   static bool on_mouse_update_;
00082   static int on_mouse_event_;
00083   static int on_mouse_x_;
00084   static int on_mouse_y_;
00085 
00086   int vmin_, vmax_, smin_;
00087   bool backprojMode;
00088   bool selectObject;
00089   int trackObject;
00090   bool showHist;
00091   cv::Point origin;
00092   cv::Rect selection;
00093   bool paused;
00094 
00095   cv::Rect trackWindow;
00096   int hsize;
00097   float hranges[2];
00098   const float* phranges;
00099   cv::Mat hist, histimg;
00100   // cv::Mat hsv;
00101 
00102   static void onMouse(int event, int x, int y, int /*unused*/, void* /*unused*/)
00103   {
00104     on_mouse_update_ = true;
00105     on_mouse_event_ = event;
00106     on_mouse_x_ = x;
00107     on_mouse_y_ = y;
00108   }
00109 
00110   void reconfigureCallback(Config& new_config, uint32_t level)
00111   {
00112     config_ = new_config;
00113     vmin_ = config_.vmin;
00114     vmax_ = config_.vmax;
00115     smin_ = config_.smin;
00116   }
00117 
00118   const std::string& frameWithDefault(const std::string& frame, const std::string& image_frame)
00119   {
00120     if (frame.empty())
00121       return image_frame;
00122     return frame;
00123   }
00124 
00125   void imageCallbackWithInfo(const sensor_msgs::ImageConstPtr& msg, const sensor_msgs::CameraInfoConstPtr& cam_info)
00126   {
00127     doWork(msg, cam_info->header.frame_id);
00128   }
00129 
00130   void imageCallback(const sensor_msgs::ImageConstPtr& msg)
00131   {
00132     doWork(msg, msg->header.frame_id);
00133   }
00134 
00135   static void trackbarCallback(int /*unused*/, void* /*unused*/)
00136   {
00137     need_config_update_ = true;
00138   }
00139 
00140   void doWork(const sensor_msgs::ImageConstPtr& msg, const std::string& input_frame_from_msg)
00141   {
00142     // Work on the image.
00143     try
00144     {
00145       // Convert the image into something opencv can handle.
00146       cv::Mat frame = cv_bridge::toCvShare(msg, sensor_msgs::image_encodings::BGR8)->image;
00147       cv::Mat backproj;
00148 
00149       // Messages
00150       opencv_apps::RotatedRectStamped rect_msg;
00151       rect_msg.header = msg->header;
00152 
00153       // Do the work
00154 
00155       if (debug_view_)
00156       {
00158 
00159         cv::namedWindow(window_name_, cv::WINDOW_AUTOSIZE);
00160 
00161         cv::setMouseCallback(window_name_, onMouse, nullptr);
00162         cv::createTrackbar("Vmin", window_name_, &vmin_, 256, trackbarCallback);
00163         cv::createTrackbar("Vmax", window_name_, &vmax_, 256, trackbarCallback);
00164         cv::createTrackbar("Smin", window_name_, &smin_, 256, trackbarCallback);
00165 
00166         if (need_config_update_)
00167         {
00168           config_.vmin = vmin_;
00169           config_.vmax = vmax_;
00170           config_.smin = smin_;
00171           reconfigure_server_->updateConfig(config_);
00172           need_config_update_ = false;
00173         }
00174       }
00175 
00176       if (on_mouse_update_)
00177       {
00178         int event = on_mouse_event_;
00179         int x = on_mouse_x_;
00180         int y = on_mouse_y_;
00181 
00182         if (selectObject)
00183         {
00184           selection.x = MIN(x, origin.x);
00185           selection.y = MIN(y, origin.y);
00186           selection.width = std::abs(x - origin.x);
00187           selection.height = std::abs(y - origin.y);
00188 
00189           selection &= cv::Rect(0, 0, frame.cols, frame.rows);
00190         }
00191 
00192         switch (event)
00193         {
00194           case cv::EVENT_LBUTTONDOWN:
00195             origin = cv::Point(x, y);
00196             selection = cv::Rect(x, y, 0, 0);
00197             selectObject = true;
00198             break;
00199           case cv::EVENT_LBUTTONUP:
00200             selectObject = false;
00201             if (selection.width > 0 && selection.height > 0)
00202               trackObject = -1;
00203             break;
00204         }
00205         on_mouse_update_ = false;
00206       }
00207 
00208       if (!paused)
00209       {
00210         cv::Mat hsv, hue, mask;
00211         cv::cvtColor(frame, hsv, cv::COLOR_BGR2HSV);
00212 
00213         if (trackObject)
00214         {
00215           int vmin = vmin_, vmax = vmax_;
00216 
00217           cv::inRange(hsv, cv::Scalar(0, smin_, MIN(vmin, vmax)), cv::Scalar(180, 256, MAX(vmin, vmax)), mask);
00218           int ch[] = { 0, 0 };
00219           hue.create(hsv.size(), hsv.depth());
00220           cv::mixChannels(&hsv, 1, &hue, 1, ch, 1);
00221 
00222           if (trackObject < 0)
00223           {
00224             cv::Mat roi(hue, selection), maskroi(mask, selection);
00225             cv::calcHist(&roi, 1, nullptr, maskroi, hist, 1, &hsize, &phranges);
00226             cv::normalize(hist, hist, 0, 255, cv::NORM_MINMAX);
00227             std::vector<float> hist_value;
00228             hist_value.resize(hsize);
00229             for (int i = 0; i < hsize; i++)
00230             {
00231               hist_value[i] = hist.at<float>(i);
00232             }
00233             pnh_->setParam("histogram", hist_value);
00234 
00235             trackWindow = selection;
00236             trackObject = 1;
00237 
00238             histimg = cv::Scalar::all(0);
00239             int bin_w = histimg.cols / hsize;
00240             cv::Mat buf(1, hsize, CV_8UC3);
00241             for (int i = 0; i < hsize; i++)
00242               buf.at<cv::Vec3b>(i) = cv::Vec3b(cv::saturate_cast<uchar>(i * 180. / hsize), 255, 255);
00243             cv::cvtColor(buf, buf, cv::COLOR_HSV2BGR);
00244 
00245             for (int i = 0; i < hsize; i++)
00246             {
00247               int val = cv::saturate_cast<int>(hist.at<float>(i) * histimg.rows / 255);
00248               cv::rectangle(histimg, cv::Point(i * bin_w, histimg.rows), cv::Point((i + 1) * bin_w, histimg.rows - val),
00249                             cv::Scalar(buf.at<cv::Vec3b>(i)), -1, 8);
00250             }
00251           }
00252 
00253           cv::calcBackProject(&hue, 1, nullptr, hist, backproj, &phranges);
00254           backproj &= mask;
00255           cv::RotatedRect track_box = cv::CamShift(
00256               backproj, trackWindow, cv::TermCriteria(cv::TermCriteria::EPS + cv::TermCriteria::MAX_ITER, 10, 1));
00257           if (trackWindow.area() <= 1)
00258           {
00259             int cols = backproj.cols, rows = backproj.rows, r = (MIN(cols, rows) + 5) / 6;
00260             // trackWindow = cv::Rect(trackWindow.x - r, trackWindow.y - r,
00261             //                       trackWindow.x + r, trackWindow.y + r) &
00262             trackWindow = cv::Rect(cols / 2 - r, rows / 2 - r, cols / 2 + r, rows / 2 + r) & cv::Rect(0, 0, cols, rows);
00263           }
00264 
00265           if (backprojMode)
00266             cv::cvtColor(backproj, frame, cv::COLOR_GRAY2BGR);
00267 #ifndef CV_VERSION_EPOCH
00268           cv::ellipse(frame, track_box, cv::Scalar(0, 0, 255), 3, cv::LINE_AA);
00269 #else
00270           cv::ellipse(frame, track_box, cv::Scalar(0, 0, 255), 3, CV_AA);
00271 #endif
00272 
00273           rect_msg.rect.angle = track_box.angle;
00274           opencv_apps::Point2D point_msg;
00275           opencv_apps::Size size_msg;
00276           point_msg.x = track_box.center.x;
00277           point_msg.y = track_box.center.y;
00278           size_msg.width = track_box.size.width;
00279           size_msg.height = track_box.size.height;
00280           rect_msg.rect.center = point_msg;
00281           rect_msg.rect.size = size_msg;
00282         }
00283       }
00284       else if (trackObject < 0)
00285         paused = false;
00286 
00287       if (selectObject && selection.width > 0 && selection.height > 0)
00288       {
00289         cv::Mat roi(frame, selection);
00290         bitwise_not(roi, roi);
00291       }
00292 
00293       if (debug_view_)
00294       {
00295         cv::imshow(window_name_, frame);
00296         cv::imshow(histogram_name_, histimg);
00297 
00298         char c = (char)cv::waitKey(1);
00299         // if( c == 27 )
00300         //  break;
00301         switch (c)
00302         {
00303           case 'b':
00304             backprojMode = !backprojMode;
00305             break;
00306           case 'c':
00307             trackObject = 0;
00308             histimg = cv::Scalar::all(0);
00309             break;
00310           case 'h':
00311             showHist = !showHist;
00312             if (!showHist)
00313               cv::destroyWindow(histogram_name_);
00314             else
00315               cv::namedWindow(histogram_name_, 1);
00316             break;
00317           case 'p':
00318             paused = !paused;
00319             break;
00320           default:;
00321         }
00322       }
00323 
00324       // Publish the image.
00325       sensor_msgs::Image::Ptr out_img1 = cv_bridge::CvImage(msg->header, msg->encoding, frame).toImageMsg();
00326       sensor_msgs::Image::Ptr out_img2 =
00327           cv_bridge::CvImage(msg->header, sensor_msgs::image_encodings::MONO8, backproj).toImageMsg();
00328       img_pub_.publish(out_img1);
00329       bproj_pub_.publish(out_img2);
00330       if (trackObject)
00331         msg_pub_.publish(rect_msg);
00332     }
00333     catch (cv::Exception& e)
00334     {
00335       NODELET_ERROR("Image processing error: %s %s %s %i", e.err.c_str(), e.func.c_str(), e.file.c_str(), e.line);
00336     }
00337 
00338     prev_stamp_ = msg->header.stamp;
00339   }
00340 
00341   void subscribe()  // NOLINT(modernize-use-override)
00342   {
00343     NODELET_DEBUG("Subscribing to image topic.");
00344     if (config_.use_camera_info)
00345       cam_sub_ = it_->subscribeCamera("image", queue_size_, &CamShiftNodelet::imageCallbackWithInfo, this);
00346     else
00347       img_sub_ = it_->subscribe("image", queue_size_, &CamShiftNodelet::imageCallback, this);
00348   }
00349 
00350   void unsubscribe()  // NOLINT(modernize-use-override)
00351   {
00352     NODELET_DEBUG("Unsubscribing from image topic.");
00353     img_sub_.shutdown();
00354     cam_sub_.shutdown();
00355   }
00356 
00357 public:
00358   virtual void onInit()  // NOLINT(modernize-use-override)
00359   {
00360     Nodelet::onInit();
00361     it_ = boost::shared_ptr<image_transport::ImageTransport>(new image_transport::ImageTransport(*nh_));
00362 
00363     pnh_->param("queue_size", queue_size_, 3);
00364     pnh_->param("debug_view", debug_view_, false);
00365     if (debug_view_)
00366     {
00367       always_subscribe_ = true;
00368     }
00369     prev_stamp_ = ros::Time(0, 0);
00370 
00371     window_name_ = "CamShift Demo";
00372     histogram_name_ = "Histogram";
00373 
00374     vmin_ = 10;
00375     vmax_ = 256;
00376     smin_ = 30;
00377     backprojMode = false;
00378     selectObject = false;
00379     trackObject = 0;
00380     showHist = true;
00381     paused = false;
00382 
00383     hsize = 16;
00384     hranges[0] = 0;
00385     hranges[1] = 180;
00386     phranges = hranges;
00387     histimg = cv::Mat::zeros(200, 320, CV_8UC3);
00388 
00389     reconfigure_server_ = boost::make_shared<dynamic_reconfigure::Server<Config> >(*pnh_);
00390     dynamic_reconfigure::Server<Config>::CallbackType f =
00391         boost::bind(&CamShiftNodelet::reconfigureCallback, this, _1, _2);
00392     reconfigure_server_->setCallback(f);
00393 
00394     img_pub_ = advertiseImage(*pnh_, "image", 1);
00395     bproj_pub_ = advertiseImage(*pnh_, "back_project", 1);
00396     msg_pub_ = advertise<opencv_apps::RotatedRectStamped>(*pnh_, "track_box", 1);
00397 
00398     NODELET_INFO("Hot keys: ");
00399     NODELET_INFO("\tESC - quit the program");
00400     NODELET_INFO("\tc - stop the tracking");
00401     NODELET_INFO("\tb - switch to/from backprojection view");
00402     NODELET_INFO("\th - show/hide object histogram");
00403     NODELET_INFO("\tp - pause video");
00404     NODELET_INFO("To initialize tracking, select the object with mouse");
00405 
00406     std::vector<float> hist_value;
00407     pnh_->getParam("histogram", hist_value);
00408     if (hist_value.size() == hsize)
00409     {
00410       hist.create(hsize, 1, CV_32F);
00411       for (int i = 0; i < hsize; i++)
00412       {
00413         hist.at<float>(i) = hist_value[i];
00414       }
00415       trackObject = 1;
00416       trackWindow = cv::Rect(0, 0, 640, 480);  //
00417 
00418       histimg = cv::Scalar::all(0);
00419       int bin_w = histimg.cols / hsize;
00420       cv::Mat buf(1, hsize, CV_8UC3);
00421       for (int i = 0; i < hsize; i++)
00422         buf.at<cv::Vec3b>(i) = cv::Vec3b(cv::saturate_cast<uchar>(i * 180. / hsize), 255, 255);
00423       cv::cvtColor(buf, buf, cv::COLOR_HSV2BGR);
00424 
00425       for (int i = 0; i < hsize; i++)
00426       {
00427         int val = cv::saturate_cast<int>(hist.at<float>(i) * histimg.rows / 255);
00428         cv::rectangle(histimg, cv::Point(i * bin_w, histimg.rows), cv::Point((i + 1) * bin_w, histimg.rows - val),
00429                       cv::Scalar(buf.at<cv::Vec3b>(i)), -1, 8);
00430       }
00431     }
00432     onInitPostProcess();
00433   }
00434 };
00435 bool CamShiftNodelet::need_config_update_ = false;
00436 bool CamShiftNodelet::on_mouse_update_ = false;
00437 int CamShiftNodelet::on_mouse_event_ = 0;
00438 int CamShiftNodelet::on_mouse_x_ = 0;
00439 int CamShiftNodelet::on_mouse_y_ = 0;
00440 }  // namespace opencv_apps
00441 
00442 namespace camshift
00443 {
00444 class CamShiftNodelet : public opencv_apps::CamShiftNodelet
00445 {
00446 public:
00447   virtual void onInit()  // NOLINT(modernize-use-override)
00448   {
00449     ROS_WARN("DeprecationWarning: Nodelet camshift/camshift is deprecated, "
00450              "and renamed to opencv_apps/camshift.");
00451     opencv_apps::CamShiftNodelet::onInit();
00452   }
00453 };
00454 }  // namespace camshift
00455 
00456 #include <pluginlib/class_list_macros.h>
00457 PLUGINLIB_EXPORT_CLASS(opencv_apps::CamShiftNodelet, nodelet::Nodelet);
00458 PLUGINLIB_EXPORT_CLASS(camshift::CamShiftNodelet, nodelet::Nodelet);


opencv_apps
Author(s): Kei Okada
autogenerated on Mon Apr 22 2019 02:18:26