46 #include <opencv2/highgui/highgui.hpp>
47 #include <opencv2/imgproc/imgproc.hpp>
49 #include <dynamic_reconfigure/server.h>
50 #include "opencv_apps/WatershedSegmentationConfig.h"
51 #include "opencv_apps/Contour.h"
52 #include "opencv_apps/ContourArray.h"
53 #include "opencv_apps/ContourArrayStamped.h"
54 #include "opencv_apps/Point2DArray.h"
68 typedef opencv_apps::WatershedSegmentationConfig
Config;
88 static void onMouse(
int event,
int x,
int y,
int flags,
void* )
97 void reconfigureCallback(opencv_apps::WatershedSegmentationConfig& new_config, uint32_t level)
102 const std::string&
frameWithDefault(
const std::string& frame,
const std::string& image_frame)
109 void imageCallbackWithInfo(
const sensor_msgs::ImageConstPtr& msg,
const sensor_msgs::CameraInfoConstPtr& cam_info)
111 doWork(msg, cam_info->header.frame_id);
116 doWork(msg, msg->header.frame_id);
124 void doWork(
const sensor_msgs::ImageConstPtr& msg,
const std::string& input_frame_from_msg)
133 opencv_apps::ContourArrayStamped contours_msg;
134 contours_msg.header = msg->header;
146 cv::cvtColor(frame, tmp, cv::COLOR_BGR2GRAY);
166 if (x < 0 || x >= frame.cols || y < 0 || y >= frame.rows)
168 if (event == cv::EVENT_LBUTTONUP || !(flags & cv::EVENT_FLAG_LBUTTON))
169 prevPt = cv::Point(-1, -1);
170 else if (event == cv::EVENT_LBUTTONDOWN)
172 else if (event == cv::EVENT_MOUSEMOVE && (flags & cv::EVENT_FLAG_LBUTTON))
178 cv::line(frame,
prevPt, pt, cv::Scalar::all(255), 5, 8, 0);
186 int i, j, comp_count = 0;
187 std::vector<std::vector<cv::Point> > contours;
188 std::vector<cv::Vec4i> hierarchy;
190 cv::findContours(
markerMask, contours, hierarchy, CV_RETR_CCOMP, CV_CHAIN_APPROX_SIMPLE);
192 if (contours.empty())
198 markers = cv::Scalar::all(0);
200 for (; idx >= 0; idx = hierarchy[idx][0], comp_count++)
201 cv::drawContours(markers, contours, idx, cv::Scalar::all(comp_count + 1), -1, 8, hierarchy, INT_MAX);
208 for (
const std::vector<cv::Point>& contour : contours)
210 opencv_apps::Contour contour_msg;
211 for (
const cv::Point& j : contour)
213 opencv_apps::Point2D point_msg;
216 contour_msg.points.push_back(point_msg);
218 contours_msg.contours.push_back(contour_msg);
221 std::vector<cv::Vec3b> color_tab;
222 for (i = 0; i < comp_count; i++)
224 int b = cv::theRNG().uniform(0, 255);
225 int g = cv::theRNG().uniform(0, 255);
226 int r = cv::theRNG().uniform(0, 255);
228 color_tab.push_back(cv::Vec3b((uchar)b, (uchar)g, (uchar)r));
231 double t = (double)cv::getTickCount();
232 cv::watershed(frame, markers);
233 t = (double)cv::getTickCount() -
t;
234 NODELET_INFO(
"execution time = %gms",
t * 1000. / cv::getTickFrequency());
236 cv::Mat wshed(markers.size(), CV_8UC3);
239 for (i = 0; i < markers.rows; i++)
240 for (j = 0; j < markers.cols; j++)
242 int index = markers.at<
int>(i, j);
244 wshed.at<cv::Vec3b>(i, j) = cv::Vec3b(255, 255, 255);
245 else if (index <= 0 || index > comp_count)
246 wshed.at<cv::Vec3b>(i, j) = cv::Vec3b(0, 0, 0);
248 wshed.at<cv::Vec3b>(i, j) = color_tab[index - 1];
251 wshed = wshed * 0.5 +
img_gray * 0.5;
258 int c = cv::waitKey(1);
272 catch (cv::Exception& e)
274 NODELET_ERROR(
"Image processing error: %s %s %s %i", e.err.c_str(), e.func.c_str(), e.file.c_str(), e.line);
282 if (msg.points.empty())
288 for (
const opencv_apps::Point2D& point : msg.points)
290 cv::Point pt0(point.x, point.y);
291 cv::Point pt1(pt0.x + 1, pt0.y + 1);
292 cv::line(
markerMask, pt0, pt1, cv::Scalar::all(255), 5, 8, 0);
327 window_name_ =
"roughly mark the areas to segment on the image";
333 dynamic_reconfigure::Server<Config>::CallbackType
f = boost::bind(
339 msg_pub_ = advertise<opencv_apps::ContourArrayStamped>(*
pnh_,
"contours", 1);
341 NODELET_INFO(
"This program demonstrates the famous watershed segmentation algorithm in OpenCV: watershed()");
345 NODELET_INFO(
"\tw or SPACE - run watershed segmentation algorithm");
346 NODELET_INFO(
"\t\t(before running it, *roughly* mark the areas to segment on the image)");
347 NODELET_INFO(
"\t (before that, roughly outline several markers on the image)");
367 ROS_WARN(
"DeprecationWarning: Nodelet watershed_segmentation/watershed_segmentation is deprecated, "
368 "and renamed to opencv_apps/watershed_segmentation.");
374 #ifdef USE_PLUGINLIB_CLASS_LIST_MACROS_H