hough_circles_nodelet.cpp
Go to the documentation of this file.
00001 // -*- coding:utf-8-unix; mode: c++; indent-tabs-mode: nil; c-basic-offset: 2; -*-
00002 /*********************************************************************
00003 * Software License Agreement (BSD License)
00004 *
00005 *  Copyright (c) 2014, Kei Okada.
00006 *  All rights reserved.
00007 *
00008 *  Redistribution and use in source and binary forms, with or without
00009 *  modification, are permitted provided that the following conditions
00010 *  are met:
00011 *
00012 *   * Redistributions of source code must retain the above copyright
00013 *     notice, this list of conditions and the following disclaimer.
00014 *   * Redistributions in binary form must reproduce the above
00015 *     copyright notice, this list of conditions and the following
00016 *     disclaimer in the documentation and/or other materials provided
00017 *     with the distribution.
00018 *   * Neither the name of the Kei Okada nor the names of its
00019 *     contributors may be used to endorse or promote products derived
00020 *     from this software without specific prior written permission.
00021 *
00022 *  THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
00023 *  "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
00024 *  LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
00025 *  FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
00026 *  COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
00027 *  INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
00028 *  BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
00029 *  LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
00030 *  CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
00031 *  LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
00032 *  ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
00033 *  POSSIBILITY OF SUCH DAMAGE.
00034 *********************************************************************/
00035 
00036 // https://github.com/Itseez/opencv/blob/2.4/samples/cpp/tutorial_code/ImgTrans/HoughCircle_Demo.cpp
00043 #include <ros/ros.h>
00044 #include "opencv_apps/nodelet.h"
00045 #include <image_transport/image_transport.h>
00046 #include <cv_bridge/cv_bridge.h>
00047 #include <sensor_msgs/image_encodings.h>
00048 
00049 #include <opencv2/highgui/highgui.hpp>
00050 #include <opencv2/imgproc/imgproc.hpp>
00051 
00052 #include <dynamic_reconfigure/server.h>
00053 #include "opencv_apps/HoughCirclesConfig.h"
00054 #include "opencv_apps/Circle.h"
00055 #include "opencv_apps/CircleArray.h"
00056 #include "opencv_apps/CircleArrayStamped.h"
00057 
00058 namespace opencv_apps
00059 {
00060 class HoughCirclesNodelet : public opencv_apps::Nodelet
00061 {
00062   image_transport::Publisher img_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 opencv_apps::HoughCirclesConfig Config;
00070   typedef dynamic_reconfigure::Server<Config> ReconfigureServer;
00071   Config config_;
00072   boost::shared_ptr<ReconfigureServer> reconfigure_server_;
00073 
00074   int queue_size_;
00075   bool debug_view_;
00076   ros::Time prev_stamp_;
00077 
00078   std::string window_name_;
00079   static bool need_config_update_;
00080 
00081   // initial and max values of the parameters of interests.
00082   int canny_threshold_initial_value_;
00083   int accumulator_threshold_initial_value_;
00084   int max_accumulator_threshold_;
00085   int max_canny_threshold_;
00086   double canny_threshold_;
00087   int canny_threshold_int;  // for trackbar
00088   double accumulator_threshold_;
00089   int accumulator_threshold_int;
00090   int gaussian_blur_size_;
00091   double gaussian_sigma_x_;
00092   int gaussian_sigma_x_int;
00093   double gaussian_sigma_y_;
00094   int gaussian_sigma_y_int;
00095   int voting_threshold_;
00096   double min_distance_between_circles_;
00097   int min_distance_between_circles_int;
00098   double dp_;
00099   int dp_int;
00100   int min_circle_radius_;
00101   int max_circle_radius_;
00102 
00103   image_transport::Publisher debug_image_pub_;
00104   int debug_image_type_;
00105 
00106   void reconfigureCallback(Config& new_config, uint32_t level)
00107   {
00108     config_ = new_config;
00109     canny_threshold_ = config_.canny_threshold;
00110     accumulator_threshold_ = config_.accumulator_threshold;
00111     gaussian_blur_size_ = config_.gaussian_blur_size;
00112     gaussian_sigma_x_ = config_.gaussian_sigma_x;
00113     gaussian_sigma_y_ = config_.gaussian_sigma_y;
00114 
00115     dp_ = config_.dp;
00116     min_circle_radius_ = config_.min_circle_radius;
00117     max_circle_radius_ = config_.max_circle_radius;
00118     debug_image_type_ = config_.debug_image_type;
00119     min_distance_between_circles_ = config_.min_distance_between_circles;
00120     canny_threshold_int = int(canny_threshold_);
00121     accumulator_threshold_int = int(accumulator_threshold_);
00122     gaussian_sigma_x_int = int(gaussian_sigma_x_);
00123     gaussian_sigma_y_int = int(gaussian_sigma_y_);
00124     min_distance_between_circles_int = int(min_distance_between_circles_);
00125     dp_int = int(dp_);
00126   }
00127 
00128   const std::string& frameWithDefault(const std::string& frame, const std::string& image_frame)
00129   {
00130     if (frame.empty())
00131       return image_frame;
00132     return frame;
00133   }
00134 
00135   void imageCallbackWithInfo(const sensor_msgs::ImageConstPtr& msg, const sensor_msgs::CameraInfoConstPtr& cam_info)
00136   {
00137     doWork(msg, cam_info->header.frame_id);
00138   }
00139 
00140   void imageCallback(const sensor_msgs::ImageConstPtr& msg)
00141   {
00142     doWork(msg, msg->header.frame_id);
00143   }
00144 
00145   static void trackbarCallback(int value, void* userdata)
00146   {
00147     need_config_update_ = true;
00148   }
00149 
00150   void doWork(const sensor_msgs::ImageConstPtr& msg, const std::string& input_frame_from_msg)
00151   {
00152     // Work on the image.
00153     try
00154     {
00155       // Convert the image into something opencv can handle.
00156       cv::Mat frame = cv_bridge::toCvShare(msg, sensor_msgs::image_encodings::BGR8)->image;
00157 
00158       // Messages
00159       opencv_apps::CircleArrayStamped circles_msg;
00160       circles_msg.header = msg->header;
00161 
00162       // Do the work
00163       std::vector<cv::Rect> faces;
00164       cv::Mat src_gray, edges;
00165 
00166       if (frame.channels() > 1)
00167       {
00168         cv::cvtColor(frame, src_gray, cv::COLOR_BGR2GRAY);
00169       }
00170       else
00171       {
00172         src_gray = frame;
00173       }
00174 
00175       // create the main window, and attach the trackbars
00176       if (debug_view_)
00177       {
00178         cv::namedWindow(window_name_, cv::WINDOW_AUTOSIZE);
00179 
00180         cv::createTrackbar("Canny Threshold", window_name_, &canny_threshold_int, max_canny_threshold_,
00181                            trackbarCallback);
00182         cv::createTrackbar("Accumulator Threshold", window_name_, &accumulator_threshold_int,
00183                            max_accumulator_threshold_, trackbarCallback);
00184         cv::createTrackbar("Gaussian Blur Size", window_name_, &gaussian_blur_size_, 30, trackbarCallback);
00185         cv::createTrackbar("Gaussian Sigam X", window_name_, &gaussian_sigma_x_int, 10, trackbarCallback);
00186         cv::createTrackbar("Gaussian Sigma Y", window_name_, &gaussian_sigma_y_int, 10, trackbarCallback);
00187         cv::createTrackbar("Min Distance between Circles", window_name_, &min_distance_between_circles_int, 100,
00188                            trackbarCallback);
00189         cv::createTrackbar("Dp", window_name_, &dp_int, 100, trackbarCallback);
00190         cv::createTrackbar("Min Circle Radius", window_name_, &min_circle_radius_, 500, trackbarCallback);
00191         cv::createTrackbar("Max Circle Radius", window_name_, &max_circle_radius_, 2000, trackbarCallback);
00192 
00193         if (need_config_update_)
00194         {
00195           config_.canny_threshold = canny_threshold_ = (double)canny_threshold_int;
00196           config_.accumulator_threshold = accumulator_threshold_ = (double)accumulator_threshold_int;
00197           config_.gaussian_blur_size = gaussian_blur_size_;
00198           config_.gaussian_sigma_x = gaussian_sigma_x_ = (double)gaussian_sigma_x_int;
00199           config_.gaussian_sigma_y = gaussian_sigma_y_ = (double)gaussian_sigma_y_int;
00200           config_.min_distance_between_circles = min_distance_between_circles_ =
00201               (double)min_distance_between_circles_int;
00202           config_.dp = dp_ = (double)dp_int;
00203           config_.min_circle_radius = min_circle_radius_;
00204           config_.max_circle_radius = max_circle_radius_;
00205           reconfigure_server_->updateConfig(config_);
00206           need_config_update_ = false;
00207         }
00208       }
00209 
00210       // Reduce the noise so we avoid false circle detection
00211       // gaussian_blur_size_ must be odd number
00212       if (gaussian_blur_size_ % 2 != 1)
00213       {
00214         gaussian_blur_size_ = gaussian_blur_size_ + 1;
00215       }
00216       cv::GaussianBlur(src_gray, src_gray, cv::Size(gaussian_blur_size_, gaussian_blur_size_), gaussian_sigma_x_,
00217                        gaussian_sigma_y_);
00218 
00219       // those paramaters cannot be =0
00220       // so we must check here
00221       canny_threshold_ = std::max(canny_threshold_, 1.0);
00222       accumulator_threshold_ = std::max(accumulator_threshold_, 1.0);
00223 
00224       if (debug_view_)
00225       {
00226         // https://github.com/Itseez/opencv/blob/2.4.8/modules/imgproc/src/hough.cpp#L817
00227         cv::Canny(frame, edges, MAX(canny_threshold_ / 2, 1), canny_threshold_, 3);
00228       }
00229       if (min_distance_between_circles_ == 0)
00230       {  // set inital value
00231         min_distance_between_circles_ = src_gray.rows / 8;
00232         config_.min_distance_between_circles = min_distance_between_circles_;
00233         reconfigure_server_->updateConfig(config_);
00234       }
00235       // runs the detection, and update the display
00236       // will hold the results of the detection
00237       std::vector<cv::Vec3f> circles;
00238       // runs the actual detection
00239       cv::HoughCircles(src_gray, circles, CV_HOUGH_GRADIENT, dp_, min_distance_between_circles_, canny_threshold_,
00240                        accumulator_threshold_, min_circle_radius_, max_circle_radius_);
00241 
00242       cv::Mat out_image;
00243       if (frame.channels() == 1)
00244       {
00245         cv::cvtColor(frame, out_image, cv::COLOR_GRAY2BGR);
00246       }
00247       else
00248       {
00249         out_image = frame;
00250       }
00251 
00252       // clone the colour, input image for displaying purposes
00253       for (const cv::Vec3f& i : circles)
00254       {
00255         cv::Point center(cvRound(i[0]), cvRound(i[1]));
00256         int radius = cvRound(i[2]);
00257         // circle center
00258         circle(out_image, center, 3, cv::Scalar(0, 255, 0), -1, 8, 0);
00259         // circle outline
00260         circle(out_image, center, radius, cv::Scalar(0, 0, 255), 3, 8, 0);
00261 
00262         opencv_apps::Circle circle_msg;
00263         circle_msg.center.x = center.x;
00264         circle_msg.center.y = center.y;
00265         circle_msg.radius = radius;
00266         circles_msg.circles.push_back(circle_msg);
00267       }
00268 
00269       // shows the results
00270       if (debug_view_ || debug_image_pub_.getNumSubscribers() > 0)
00271       {
00272         cv::Mat debug_image;
00273         switch (debug_image_type_)
00274         {
00275           case 1:
00276             debug_image = src_gray;
00277             break;
00278           case 2:
00279             debug_image = edges;
00280             break;
00281           default:
00282             debug_image = frame;
00283             break;
00284         }
00285         if (debug_view_)
00286         {
00287           cv::imshow(window_name_, debug_image);
00288           int c = cv::waitKey(1);
00289           if (c == 's')
00290           {
00291             debug_image_type_ = (++debug_image_type_) % 3;
00292             config_.debug_image_type = debug_image_type_;
00293             reconfigure_server_->updateConfig(config_);
00294           }
00295         }
00296         if (debug_image_pub_.getNumSubscribers() > 0)
00297         {
00298           sensor_msgs::Image::Ptr out_debug_img =
00299               cv_bridge::CvImage(msg->header, msg->encoding, debug_image).toImageMsg();
00300           debug_image_pub_.publish(out_debug_img);
00301         }
00302       }
00303 
00304       // Publish the image.
00305       sensor_msgs::Image::Ptr out_img = cv_bridge::CvImage(msg->header, "bgr8", out_image).toImageMsg();
00306       img_pub_.publish(out_img);
00307       msg_pub_.publish(circles_msg);
00308     }
00309     catch (cv::Exception& e)
00310     {
00311       NODELET_ERROR("Image processing error: %s %s %s %i", e.err.c_str(), e.func.c_str(), e.file.c_str(), e.line);
00312     }
00313 
00314     prev_stamp_ = msg->header.stamp;
00315   }
00316 
00317   void subscribe()  // NOLINT(modernize-use-override)
00318   {
00319     NODELET_DEBUG("Subscribing to image topic.");
00320     if (config_.use_camera_info)
00321       cam_sub_ = it_->subscribeCamera("image", queue_size_, &HoughCirclesNodelet::imageCallbackWithInfo, this);
00322     else
00323       img_sub_ = it_->subscribe("image", queue_size_, &HoughCirclesNodelet::imageCallback, this);
00324   }
00325 
00326   void unsubscribe()  // NOLINT(modernize-use-override)
00327   {
00328     NODELET_DEBUG("Unsubscribing from image topic.");
00329     img_sub_.shutdown();
00330     cam_sub_.shutdown();
00331   }
00332 
00333 public:
00334   virtual void onInit()  // NOLINT(modernize-use-override)
00335   {
00336     Nodelet::onInit();
00337     it_ = boost::shared_ptr<image_transport::ImageTransport>(new image_transport::ImageTransport(*nh_));
00338 
00339     debug_image_type_ = 0;
00340     pnh_->param("queue_size", queue_size_, 3);
00341     pnh_->param("debug_view", debug_view_, false);
00342     if (debug_view_)
00343     {
00344       always_subscribe_ = debug_view_;
00345     }
00346     prev_stamp_ = ros::Time(0, 0);
00347 
00348     window_name_ = "Hough Circle Detection Demo";
00349     canny_threshold_initial_value_ = 200;
00350     accumulator_threshold_initial_value_ = 50;
00351     max_accumulator_threshold_ = 200;
00352     max_canny_threshold_ = 255;
00353     min_distance_between_circles_ = 0;
00354 
00355     // declare and initialize both parameters that are subjects to change
00356     canny_threshold_ = canny_threshold_initial_value_;
00357     accumulator_threshold_ = accumulator_threshold_initial_value_;
00358 
00359     reconfigure_server_ = boost::make_shared<dynamic_reconfigure::Server<Config> >(*pnh_);
00360     dynamic_reconfigure::Server<Config>::CallbackType f =
00361         boost::bind(&HoughCirclesNodelet::reconfigureCallback, this, _1, _2);
00362     reconfigure_server_->setCallback(f);
00363 
00364     img_pub_ = advertiseImage(*pnh_, "image", 1);
00365     msg_pub_ = advertise<opencv_apps::CircleArrayStamped>(*pnh_, "circles", 1);
00366 
00367     debug_image_type_ = 0;
00368     debug_image_pub_ = advertiseImage(*pnh_, "debug_image", 1);
00369 
00370     onInitPostProcess();
00371   }
00372 };
00373 bool HoughCirclesNodelet::need_config_update_ = false;
00374 }  // namespace opencv_apps
00375 
00376 namespace hough_circles
00377 {
00378 class HoughCirclesNodelet : public opencv_apps::HoughCirclesNodelet
00379 {
00380 public:
00381   virtual void onInit()  // NOLINT(modernize-use-override)
00382   {
00383     ROS_WARN("DeprecationWarning: Nodelet hough_circles/hough_circles is deprecated, "
00384              "and renamed to opencv_apps/hough_circles.");
00385     opencv_apps::HoughCirclesNodelet::onInit();
00386   }
00387 };
00388 }  // namespace hough_circles
00389 
00390 #include <pluginlib/class_list_macros.h>
00391 PLUGINLIB_EXPORT_CLASS(opencv_apps::HoughCirclesNodelet, nodelet::Nodelet);
00392 PLUGINLIB_EXPORT_CLASS(hough_circles::HoughCirclesNodelet, nodelet::Nodelet);


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