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 hough_circles {
00059 class HoughCirclesNodelet : public opencv_apps::Nodelet
00060 {
00061   image_transport::Publisher img_pub_;
00062   image_transport::Subscriber img_sub_;
00063   image_transport::CameraSubscriber cam_sub_;
00064   ros::Publisher msg_pub_;
00065 
00066   boost::shared_ptr<image_transport::ImageTransport> it_;
00067 
00068   typedef hough_circles::HoughCirclesConfig Config;
00069   typedef dynamic_reconfigure::Server<Config> ReconfigureServer;
00070   Config config_;
00071   boost::shared_ptr<ReconfigureServer> reconfigure_server_;
00072 
00073   bool debug_view_;
00074   ros::Time prev_stamp_;
00075 
00076   std::string window_name_;
00077   static bool need_config_update_;
00078 
00079   // initial and max values of the parameters of interests.
00080   int canny_threshold_initial_value_;
00081   int accumulator_threshold_initial_value_;
00082   int max_accumulator_threshold_;
00083   int max_canny_threshold_;
00084   double canny_threshold_; int canny_threshold_int; // for trackbar
00085   double accumulator_threshold_; int accumulator_threshold_int;
00086   int gaussian_blur_size_;
00087   double gaussian_sigma_x_; int gaussian_sigma_x_int;
00088   double gaussian_sigma_y_; int gaussian_sigma_y_int;
00089   int voting_threshold_;
00090   double min_distance_between_circles_; int min_distance_between_circles_int;
00091   double dp_; int dp_int;
00092   int min_circle_radius_;
00093   int max_circle_radius_;
00094 
00095   image_transport::Publisher debug_image_pub_;
00096   int debug_image_type_;
00097 
00098   void reconfigureCallback(Config &new_config, uint32_t level)
00099   {
00100     config_ = new_config;
00101     canny_threshold_ = config_.canny_threshold;
00102     accumulator_threshold_ = config_.accumulator_threshold;
00103     gaussian_blur_size_ = config_.gaussian_blur_size;
00104     gaussian_sigma_x_ = config_.gaussian_sigma_x;
00105     gaussian_sigma_y_ = config_.gaussian_sigma_y;
00106 
00107     dp_ = config_.dp;
00108     min_circle_radius_ = config_.min_circle_radius;
00109     max_circle_radius_ = config_.max_circle_radius;
00110     debug_image_type_ = config_.debug_image_type;
00111     min_distance_between_circles_ = config_.min_distance_between_circles;
00112     canny_threshold_int = int(canny_threshold_);
00113     accumulator_threshold_int = int(accumulator_threshold_);
00114     gaussian_sigma_x_int = int(gaussian_sigma_x_);
00115     gaussian_sigma_y_int = int(gaussian_sigma_y_);
00116     min_distance_between_circles_int = int(min_distance_between_circles_);
00117     dp_int = int(dp_);
00118   }
00119 
00120   const std::string &frameWithDefault(const std::string &frame, const std::string &image_frame)
00121   {
00122     if (frame.empty())
00123       return image_frame;
00124     return frame;
00125   }
00126 
00127   void imageCallbackWithInfo(const sensor_msgs::ImageConstPtr& msg, const sensor_msgs::CameraInfoConstPtr& cam_info)
00128   {
00129     do_work(msg, cam_info->header.frame_id);
00130   }
00131 
00132   void imageCallback(const sensor_msgs::ImageConstPtr& msg)
00133   {
00134     do_work(msg, msg->header.frame_id);
00135   }
00136 
00137   static void trackbarCallback( int value, void* userdata)
00138   {
00139     need_config_update_ = true;
00140   }
00141 
00142   void do_work(const sensor_msgs::ImageConstPtr& msg, const std::string input_frame_from_msg)
00143   {
00144     // Work on the image.
00145     try
00146     {
00147       // Convert the image into something opencv can handle.
00148       cv::Mat frame = cv_bridge::toCvShare(msg, sensor_msgs::image_encodings::BGR8)->image;
00149 
00150       // Messages
00151       opencv_apps::CircleArrayStamped circles_msg;
00152       circles_msg.header = msg->header;
00153 
00154       // Do the work
00155       std::vector<cv::Rect> faces;
00156       cv::Mat src_gray, edges;
00157 
00158       if ( frame.channels() > 1 ) {
00159         cv::cvtColor( frame, src_gray, cv::COLOR_BGR2GRAY );
00160       } else {
00161         src_gray = frame;
00162       }
00163 
00164       // create the main window, and attach the trackbars
00165       if( debug_view_) {
00166         cv::namedWindow( window_name_, cv::WINDOW_AUTOSIZE );
00167 
00168         cv::createTrackbar("Canny Threshold", window_name_, &canny_threshold_int, max_canny_threshold_, trackbarCallback);
00169         cv::createTrackbar("Accumulator Threshold", window_name_, &accumulator_threshold_int, max_accumulator_threshold_, trackbarCallback);
00170         cv::createTrackbar("Gaussian Blur Size", window_name_, &gaussian_blur_size_, 30, trackbarCallback);
00171         cv::createTrackbar("Gaussian Sigam X", window_name_, &gaussian_sigma_x_int, 10, trackbarCallback);
00172         cv::createTrackbar("Gaussian Sigma Y", window_name_, &gaussian_sigma_y_int, 10, trackbarCallback);
00173         cv::createTrackbar("Min Distance between Circles", window_name_, &min_distance_between_circles_int, 100, trackbarCallback);
00174         cv::createTrackbar("Dp", window_name_, &dp_int, 100, trackbarCallback);
00175         cv::createTrackbar("Min Circle Radius", window_name_, &min_circle_radius_, 500, trackbarCallback);
00176         cv::createTrackbar("Max Circle Radius", window_name_, &max_circle_radius_, 2000, trackbarCallback);
00177 
00178         if (need_config_update_) {
00179           config_.canny_threshold = canny_threshold_ = (double)canny_threshold_int;
00180           config_.accumulator_threshold = accumulator_threshold_ = (double)accumulator_threshold_int;
00181           config_.gaussian_blur_size = gaussian_blur_size_;
00182           config_.gaussian_sigma_x = gaussian_sigma_x_ = (double)gaussian_sigma_x_int;
00183           config_.gaussian_sigma_y = gaussian_sigma_y_ = (double)gaussian_sigma_y_int;
00184           config_.min_distance_between_circles = min_distance_between_circles_ = (double)min_distance_between_circles_int;
00185           config_.dp = dp_ = (double)dp_int;
00186           config_.min_circle_radius = min_circle_radius_;
00187           config_.max_circle_radius = max_circle_radius_;
00188           reconfigure_server_->updateConfig(config_);
00189           need_config_update_ = false;
00190         }
00191       }
00192 
00193       // Reduce the noise so we avoid false circle detection
00194       // gaussian_blur_size_ must be odd number
00195       if (gaussian_blur_size_%2 != 1) {
00196         gaussian_blur_size_ = gaussian_blur_size_ + 1;
00197       }
00198       cv::GaussianBlur( src_gray, src_gray, cv::Size(gaussian_blur_size_, gaussian_blur_size_), gaussian_sigma_x_, gaussian_sigma_y_ );
00199 
00200       // those paramaters cannot be =0
00201       // so we must check here
00202       canny_threshold_ = std::max(canny_threshold_, 1.0);
00203       accumulator_threshold_ = std::max(accumulator_threshold_, 1.0);
00204 
00205       if( debug_view_) {
00206         // https://github.com/Itseez/opencv/blob/2.4.8/modules/imgproc/src/hough.cpp#L817
00207         cv::Canny(frame, edges, MAX(canny_threshold_/2,1), canny_threshold_, 3 );
00208       }
00209       if ( min_distance_between_circles_ == 0 ) { // set inital value
00210         min_distance_between_circles_ = src_gray.rows/8;
00211         config_.min_distance_between_circles = min_distance_between_circles_;
00212         reconfigure_server_->updateConfig(config_);
00213       }
00214       //runs the detection, and update the display
00215       // will hold the results of the detection
00216       std::vector<cv::Vec3f> circles;
00217       // runs the actual detection
00218       cv::HoughCircles( src_gray, circles,
00219                         CV_HOUGH_GRADIENT,
00220                         dp_,
00221                         min_distance_between_circles_,
00222                         canny_threshold_,
00223                         accumulator_threshold_,
00224                         min_circle_radius_,
00225                         max_circle_radius_ );
00226 
00227       cv::Mat out_image;
00228       if ( frame.channels() == 1 ) {
00229         cv::cvtColor( frame, out_image, cv::COLOR_GRAY2BGR);
00230       } else {
00231         out_image = frame;
00232       }
00233 
00234       // clone the colour, input image for displaying purposes
00235       for( size_t i = 0; i < circles.size(); i++ )
00236       {
00237         cv::Point center(cvRound(circles[i][0]), cvRound(circles[i][1]));
00238         int radius = cvRound(circles[i][2]);
00239         // circle center
00240         circle( out_image, center, 3, cv::Scalar(0,255,0), -1, 8, 0 );
00241         // circle outline
00242         circle( out_image, center, radius, cv::Scalar(0,0,255), 3, 8, 0 );
00243 
00244         opencv_apps::Circle circle_msg;
00245         circle_msg.center.x = center.x;
00246         circle_msg.center.y = center.y;
00247         circle_msg.radius = radius;
00248         circles_msg.circles.push_back(circle_msg);
00249       }
00250 
00251       // shows the results
00252       if( debug_view_ || debug_image_pub_.getNumSubscribers() > 0 ) {
00253         cv::Mat debug_image;
00254         switch (debug_image_type_) {
00255           case 1:
00256             debug_image = src_gray;
00257             break;
00258           case 2:
00259             debug_image = edges;
00260             break;
00261           default:
00262             debug_image = frame;
00263             break;
00264         }
00265         if ( debug_view_ ) {
00266           cv::imshow( window_name_, debug_image );
00267           int c = cv::waitKey(1);
00268           if ( c == 's' ) {
00269             debug_image_type_ = (++debug_image_type_)%3;
00270             config_.debug_image_type = debug_image_type_;
00271             reconfigure_server_->updateConfig(config_);
00272           }
00273         }
00274         if ( debug_image_pub_.getNumSubscribers() > 0 ) {
00275           sensor_msgs::Image::Ptr out_debug_img = cv_bridge::CvImage(msg->header, msg->encoding, debug_image).toImageMsg();
00276           debug_image_pub_.publish(out_debug_img);
00277         }
00278       }
00279 
00280       // Publish the image.
00281       sensor_msgs::Image::Ptr out_img = cv_bridge::CvImage(msg->header, "bgr8", out_image).toImageMsg();
00282       img_pub_.publish(out_img);
00283       msg_pub_.publish(circles_msg);
00284     }
00285     catch (cv::Exception &e)
00286     {
00287       NODELET_ERROR("Image processing error: %s %s %s %i", e.err.c_str(), e.func.c_str(), e.file.c_str(), e.line);
00288     }
00289 
00290     prev_stamp_ = msg->header.stamp;
00291   }
00292 
00293   void subscribe()
00294   {
00295     NODELET_DEBUG("Subscribing to image topic.");
00296     if (config_.use_camera_info)
00297       cam_sub_ = it_->subscribeCamera("image", 3, &HoughCirclesNodelet::imageCallbackWithInfo, this);
00298     else
00299       img_sub_ = it_->subscribe("image", 3, &HoughCirclesNodelet::imageCallback, this);
00300   }
00301 
00302   void unsubscribe()
00303   {
00304     NODELET_DEBUG("Unsubscribing from image topic.");
00305     img_sub_.shutdown();
00306     cam_sub_.shutdown();
00307   }
00308 
00309 public:
00310   virtual void onInit()
00311   {
00312     Nodelet::onInit();
00313     it_ = boost::shared_ptr<image_transport::ImageTransport>(new image_transport::ImageTransport(*nh_));
00314 
00315     debug_image_type_ = 0;
00316     pnh_->param("debug_view", debug_view_, false);
00317     if (debug_view_) {
00318       always_subscribe_ = debug_view_;
00319     }
00320     prev_stamp_ = ros::Time(0, 0);
00321 
00322     window_name_ = "Hough Circle Detection Demo";
00323     canny_threshold_initial_value_ = 200;
00324     accumulator_threshold_initial_value_ = 50;
00325     max_accumulator_threshold_ = 200;
00326     max_canny_threshold_ = 255;
00327     min_distance_between_circles_ = 0;
00328 
00329     //declare and initialize both parameters that are subjects to change
00330     canny_threshold_ = canny_threshold_initial_value_;
00331     accumulator_threshold_ = accumulator_threshold_initial_value_;
00332 
00333     reconfigure_server_ = boost::make_shared<dynamic_reconfigure::Server<Config> >(*pnh_);
00334     dynamic_reconfigure::Server<Config>::CallbackType f =
00335       boost::bind(&HoughCirclesNodelet::reconfigureCallback, this, _1, _2);
00336     reconfigure_server_->setCallback(f);
00337 
00338     img_pub_ = advertiseImage(*pnh_, "image", 1);
00339     msg_pub_ = advertise<opencv_apps::CircleArrayStamped>(*pnh_, "circles", 1);
00340 
00341     debug_image_type_ = 0;
00342     debug_image_pub_ = advertiseImage(*pnh_, "debug_image", 1);
00343 
00344     onInitPostProcess();
00345   }
00346 };
00347 bool HoughCirclesNodelet::need_config_update_ = false;
00348 }
00349 
00350 #include <pluginlib/class_list_macros.h>
00351 PLUGINLIB_EXPORT_CLASS(hough_circles::HoughCirclesNodelet, nodelet::Nodelet);


opencv_apps
Author(s): Kei Okada
autogenerated on Tue May 2 2017 02:58:58