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;
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);
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);
237 std::vector<cv::Vec3f> circles;
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);
276 debug_image = src_gray;
288 int c = cv::waitKey(1);
298 sensor_msgs::Image::Ptr 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);
360 dynamic_reconfigure::Server<Config>::CallbackType
f =
365 msg_pub_ = advertise<opencv_apps::CircleArrayStamped>(*
pnh_,
"circles", 1);
383 ROS_WARN(
"DeprecationWarning: Nodelet hough_circles/hough_circles is deprecated, "
384 "and renamed to opencv_apps/hough_circles.");
390 #ifdef USE_PLUGINLIB_CLASS_LIST_MACROS_H