49 #include <opencv2/highgui/highgui.hpp> 50 #include <opencv2/imgproc/imgproc.hpp> 52 #include <dynamic_reconfigure/server.h> 53 #include "opencv_apps/HoughCirclesConfig.h" 54 #include "opencv_apps/Circle.h" 55 #include "opencv_apps/CircleArray.h" 56 #include "opencv_apps/CircleArrayStamped.h" 69 typedef opencv_apps::HoughCirclesConfig
Config;
108 config_ = new_config;
109 canny_threshold_ = config_.canny_threshold;
110 accumulator_threshold_ = config_.accumulator_threshold;
111 gaussian_blur_size_ = config_.gaussian_blur_size;
112 gaussian_sigma_x_ = config_.gaussian_sigma_x;
113 gaussian_sigma_y_ = config_.gaussian_sigma_y;
116 min_circle_radius_ = config_.min_circle_radius;
117 max_circle_radius_ = config_.max_circle_radius;
118 debug_image_type_ = config_.debug_image_type;
119 min_distance_between_circles_ = config_.min_distance_between_circles;
120 canny_threshold_int = int(canny_threshold_);
121 accumulator_threshold_int = int(accumulator_threshold_);
122 gaussian_sigma_x_int = int(gaussian_sigma_x_);
123 gaussian_sigma_y_int = int(gaussian_sigma_y_);
124 min_distance_between_circles_int = int(min_distance_between_circles_);
128 const std::string&
frameWithDefault(
const std::string& frame,
const std::string& image_frame)
137 doWork(msg, cam_info->header.frame_id);
142 doWork(msg, msg->header.frame_id);
147 need_config_update_ =
true;
150 void doWork(
const sensor_msgs::ImageConstPtr& msg,
const std::string& input_frame_from_msg)
159 opencv_apps::CircleArrayStamped circles_msg;
160 circles_msg.header = msg->header;
163 std::vector<cv::Rect> faces;
164 cv::Mat src_gray, edges;
166 if (frame.channels() > 1)
168 cv::cvtColor(frame, src_gray, cv::COLOR_BGR2GRAY);
178 cv::namedWindow(window_name_, cv::WINDOW_AUTOSIZE);
180 cv::createTrackbar(
"Canny Threshold", window_name_, &canny_threshold_int, max_canny_threshold_,
182 cv::createTrackbar(
"Accumulator Threshold", window_name_, &accumulator_threshold_int,
184 cv::createTrackbar(
"Gaussian Blur Size", window_name_, &gaussian_blur_size_, 30,
trackbarCallback);
185 cv::createTrackbar(
"Gaussian Sigam X", window_name_, &gaussian_sigma_x_int, 10,
trackbarCallback);
186 cv::createTrackbar(
"Gaussian Sigma Y", window_name_, &gaussian_sigma_y_int, 10,
trackbarCallback);
187 cv::createTrackbar(
"Min Distance between Circles", window_name_, &min_distance_between_circles_int, 100,
190 cv::createTrackbar(
"Min Circle Radius", window_name_, &min_circle_radius_, 500,
trackbarCallback);
191 cv::createTrackbar(
"Max Circle Radius", window_name_, &max_circle_radius_, 2000,
trackbarCallback);
193 if (need_config_update_)
195 config_.canny_threshold = canny_threshold_ = (double)canny_threshold_int;
196 config_.accumulator_threshold = accumulator_threshold_ = (double)accumulator_threshold_int;
198 config_.gaussian_sigma_x = gaussian_sigma_x_ = (double)gaussian_sigma_x_int;
199 config_.gaussian_sigma_y = gaussian_sigma_y_ = (double)gaussian_sigma_y_int;
200 config_.min_distance_between_circles = min_distance_between_circles_ =
201 (double)min_distance_between_circles_int;
202 config_.dp = dp_ = (double)dp_int;
205 reconfigure_server_->updateConfig(config_);
206 need_config_update_ =
false;
212 if (gaussian_blur_size_ % 2 != 1)
214 gaussian_blur_size_ = gaussian_blur_size_ + 1;
216 cv::GaussianBlur(src_gray, src_gray, cv::Size(gaussian_blur_size_, gaussian_blur_size_), gaussian_sigma_x_,
221 canny_threshold_ = std::max(canny_threshold_, 1.0);
222 accumulator_threshold_ = std::max(accumulator_threshold_, 1.0);
227 cv::Canny(frame, edges, MAX(canny_threshold_ / 2, 1), canny_threshold_, 3);
229 if (min_distance_between_circles_ == 0)
231 min_distance_between_circles_ = src_gray.rows / 8;
233 reconfigure_server_->updateConfig(config_);
237 std::vector<cv::Vec3f> circles;
239 cv::HoughCircles(src_gray, circles, CV_HOUGH_GRADIENT, dp_, min_distance_between_circles_, canny_threshold_,
240 accumulator_threshold_, min_circle_radius_, max_circle_radius_);
243 if (frame.channels() == 1)
245 cv::cvtColor(frame, out_image, cv::COLOR_GRAY2BGR);
253 for (
const cv::Vec3f& i : circles)
255 cv::Point center(cvRound(i[0]), cvRound(i[1]));
256 int radius = cvRound(i[2]);
258 circle(out_image, center, 3, cv::Scalar(0, 255, 0), -1, 8, 0);
260 circle(out_image, center, radius, cv::Scalar(0, 0, 255), 3, 8, 0);
262 opencv_apps::Circle circle_msg;
263 circle_msg.center.x = center.x;
264 circle_msg.center.y = center.y;
265 circle_msg.radius = radius;
266 circles_msg.circles.push_back(circle_msg);
273 switch (debug_image_type_)
276 debug_image = src_gray;
287 cv::imshow(window_name_, debug_image);
288 int c = cv::waitKey(1);
293 reconfigure_server_->updateConfig(config_);
298 sensor_msgs::Image::Ptr out_debug_img =
300 debug_image_pub_.
publish(out_debug_img);
309 catch (cv::Exception& e)
311 NODELET_ERROR(
"Image processing error: %s %s %s %i", e.err.c_str(), e.func.c_str(), e.file.c_str(), e.line);
314 prev_stamp_ = msg->header.stamp;
320 if (config_.use_camera_info)
339 debug_image_type_ = 0;
340 pnh_->param(
"queue_size", queue_size_, 3);
341 pnh_->param(
"debug_view", debug_view_,
false);
348 window_name_ =
"Hough Circle Detection Demo";
349 canny_threshold_initial_value_ = 200;
350 accumulator_threshold_initial_value_ = 50;
351 max_accumulator_threshold_ = 200;
352 max_canny_threshold_ = 255;
353 min_distance_between_circles_ = 0;
359 reconfigure_server_ = boost::make_shared<dynamic_reconfigure::Server<Config> >(*pnh_);
360 dynamic_reconfigure::Server<Config>::CallbackType
f =
362 reconfigure_server_->setCallback(f);
365 msg_pub_ = advertise<opencv_apps::CircleArrayStamped>(*
pnh_,
"circles", 1);
367 debug_image_type_ = 0;
383 ROS_WARN(
"DeprecationWarning: Nodelet hough_circles/hough_circles is deprecated, " 384 "and renamed to opencv_apps/hough_circles.");
CvImageConstPtr toCvShare(const sensor_msgs::ImageConstPtr &source, const std::string &encoding=std::string())
image_transport::Publisher debug_image_pub_
void subscribe()
This method is called when publisher is subscribed by other nodes. Set up subscribers in this method...
#define NODELET_ERROR(...)
int accumulator_threshold_initial_value_
void publish(const boost::shared_ptr< M > &message) const
void reconfigureCallback(Config &new_config, uint32_t level)
void imageCallbackWithInfo(const sensor_msgs::ImageConstPtr &msg, const sensor_msgs::CameraInfoConstPtr &cam_info)
Nodelet to automatically subscribe/unsubscribe topics according to subscription of advertised topics...
image_transport::Publisher img_pub_
Demo code to calculate moments.
double accumulator_threshold_
int canny_threshold_initial_value_
boost::shared_ptr< ros::NodeHandle > pnh_
Shared pointer to private nodehandle.
void doWork(const sensor_msgs::ImageConstPtr &msg, const std::string &input_frame_from_msg)
uint32_t getNumSubscribers() const
dynamic_reconfigure::Server< Config > ReconfigureServer
double min_distance_between_circles_
void unsubscribe()
This method is called when publisher is unsubscribed by other nodes. Shut down subscribers in this me...
bool always_subscribe_
A flag to disable watching mechanism and always subscribe input topics. It can be specified via ~alwa...
image_transport::Subscriber img_sub_
virtual void onInitPostProcess()
Post processing of initialization of nodelet. You need to call this method in order to use always_sub...
virtual void onInit()
Initialize nodehandles nh_ and pnh_. Subclass should call this method in its onInit method...
virtual void onInit()
Initialize nodehandles nh_ and pnh_. Subclass should call this method in its onInit method...
void publish(const sensor_msgs::Image &message) const
image_transport::CameraSubscriber cam_sub_
void imageCallback(const sensor_msgs::ImageConstPtr &msg)
boost::shared_ptr< ros::NodeHandle > nh_
Shared pointer to nodehandle.
int accumulator_threshold_int
PLUGINLIB_EXPORT_CLASS(opencv_apps::HoughCirclesNodelet, nodelet::Nodelet)
boost::shared_ptr< ReconfigureServer > reconfigure_server_
image_transport::Publisher advertiseImage(ros::NodeHandle &nh, const std::string &topic, int queue_size)
Advertise an image topic and watch the publisher. Publishers which are created by this method...
static void trackbarCallback(int value, void *userdata)
opencv_apps::HoughCirclesConfig Config
const std::string & frameWithDefault(const std::string &frame, const std::string &image_frame)
static bool need_config_update_
int max_accumulator_threshold_
int min_distance_between_circles_int
#define NODELET_DEBUG(...)
sensor_msgs::ImagePtr toImageMsg() const
virtual void onInit()
Initialize nodehandles nh_ and pnh_. Subclass should call this method in its onInit method...
boost::shared_ptr< image_transport::ImageTransport > it_