49 #include <opencv2/highgui/highgui.hpp>
50 #include <opencv2/imgproc/imgproc.hpp>
52 #include <dynamic_reconfigure/server.h>
53 #include "opencv_apps/ConvexHullConfig.h"
54 #include "opencv_apps/Contour.h"
55 #include "opencv_apps/ContourArray.h"
56 #include "opencv_apps/ContourArrayStamped.h"
69 typedef opencv_apps::ConvexHullConfig
Config;
89 const std::string&
frameWithDefault(
const std::string& frame,
const std::string& image_frame)
96 void imageCallbackWithInfo(
const sensor_msgs::ImageConstPtr& msg,
const sensor_msgs::CameraInfoConstPtr& cam_info)
98 doWork(msg, cam_info->header.frame_id);
103 doWork(msg, msg->header.frame_id);
111 void doWork(
const sensor_msgs::ImageConstPtr& msg,
const std::string& input_frame_from_msg)
120 opencv_apps::ContourArrayStamped contours_msg;
121 contours_msg.header = msg->header;
127 if (frame.channels() > 1)
129 cv::cvtColor(frame, src_gray, cv::COLOR_RGB2GRAY);
135 cv::blur(src_gray, src_gray, cv::Size(3, 3));
143 cv::Mat threshold_output;
144 int max_thresh = 255;
145 std::vector<std::vector<cv::Point> > contours;
146 std::vector<cv::Vec4i> hierarchy;
150 cv::threshold(src_gray, threshold_output,
threshold_, 255, cv::THRESH_BINARY);
153 cv::findContours(threshold_output, contours, hierarchy, CV_RETR_TREE, CV_CHAIN_APPROX_SIMPLE, cv::Point(0, 0));
156 std::vector<std::vector<cv::Point> > hull(contours.size());
157 for (
size_t i = 0; i < contours.size(); i++)
159 cv::convexHull(cv::Mat(contours[i]), hull[i],
false);
163 cv::Mat drawing = cv::Mat::zeros(threshold_output.size(), CV_8UC3);
164 for (
size_t i = 0; i < contours.size(); i++)
166 cv::Scalar color = cv::Scalar(rng.uniform(0, 255), rng.uniform(0, 255), rng.uniform(0, 255));
167 cv::drawContours(drawing, contours, (
int)i, color, 1, 8, std::vector<cv::Vec4i>(), 0, cv::Point());
168 cv::drawContours(drawing, hull, (
int)i, color, 4, 8, std::vector<cv::Vec4i>(), 0, cv::Point());
170 opencv_apps::Contour contour_msg;
171 for (
const cv::Point& j : hull[i])
173 opencv_apps::Point2D point_msg;
176 contour_msg.points.push_back(point_msg);
178 contours_msg.contours.push_back(contour_msg);
193 int c = cv::waitKey(1);
197 sensor_msgs::Image::Ptr out_img =
202 catch (cv::Exception& e)
204 NODELET_ERROR(
"Image processing error: %s %s %s %i", e.err.c_str(), e.func.c_str(), e.file.c_str(), e.line);
244 dynamic_reconfigure::Server<Config>::CallbackType
f =
249 msg_pub_ = advertise<opencv_apps::ContourArrayStamped>(*
pnh_,
"hulls", 1);
263 ROS_WARN(
"DeprecationWarning: Nodelet convex_hull/convex_hull is deprecated, "
264 "and renamed to opencv_apps/convex_hull.");
270 #ifdef USE_PLUGINLIB_CLASS_LIST_MACROS_H