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* )
90 on_mouse_update_ =
true;
91 on_mouse_event_ = event;
94 on_mouse_flags_ = flags;
102 const std::string&
frameWithDefault(
const std::string& frame,
const std::string& image_frame)
111 doWork(msg, cam_info->header.frame_id);
116 doWork(msg, msg->header.frame_id);
121 need_config_update_ =
true;
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;
141 if (markerMask.empty())
143 cv::cvtColor(frame, markerMask, cv::COLOR_BGR2GRAY);
144 cv::cvtColor(markerMask, img_gray, cv::COLOR_GRAY2BGR);
145 markerMask = cv::Scalar::all(0);
150 cv::imshow(window_name_, frame);
151 cv::setMouseCallback(window_name_,
onMouse,
nullptr);
152 if (need_config_update_)
154 reconfigure_server_->updateConfig(config_);
155 need_config_update_ =
false;
158 if (on_mouse_update_)
165 if (x < 0 || x >= frame.cols || y < 0 || y >= frame.rows)
167 if (event == cv::EVENT_LBUTTONUP || !(flags & cv::EVENT_FLAG_LBUTTON))
168 prevPt = cv::Point(-1, -1);
169 else if (event == cv::EVENT_LBUTTONDOWN)
170 prevPt = cv::Point(x, y);
171 else if (event == cv::EVENT_MOUSEMOVE && (flags & cv::EVENT_FLAG_LBUTTON))
176 cv::line(markerMask, prevPt, pt, cv::Scalar::all(255), 5, 8, 0);
177 cv::line(frame, prevPt, pt, cv::Scalar::all(255), 5, 8, 0);
179 cv::imshow(window_name_, markerMask);
185 int i, j, comp_count = 0;
186 std::vector<std::vector<cv::Point> > contours;
187 std::vector<cv::Vec4i> hierarchy;
189 cv::findContours(markerMask, contours, hierarchy, CV_RETR_CCOMP, CV_CHAIN_APPROX_SIMPLE);
191 if (contours.empty())
196 cv::Mat markers(markerMask.size(), CV_32S);
197 markers = cv::Scalar::all(0);
199 for (; idx >= 0; idx = hierarchy[idx][0], comp_count++)
200 cv::drawContours(markers, contours, idx, cv::Scalar::all(comp_count + 1), -1, 8, hierarchy, INT_MAX);
207 for (
const std::vector<cv::Point>& contour : contours)
209 opencv_apps::Contour contour_msg;
210 for (
const cv::Point& j : contour)
212 opencv_apps::Point2D point_msg;
215 contour_msg.points.push_back(point_msg);
217 contours_msg.contours.push_back(contour_msg);
220 std::vector<cv::Vec3b> color_tab;
221 for (i = 0; i < comp_count; i++)
223 int b = cv::theRNG().uniform(0, 255);
224 int g = cv::theRNG().uniform(0, 255);
225 int r = cv::theRNG().uniform(0, 255);
227 color_tab.push_back(cv::Vec3b((uchar)b, (uchar)g, (uchar)r));
230 double t = (double)cv::getTickCount();
231 cv::watershed(frame, markers);
232 t = (double)cv::getTickCount() -
t;
233 NODELET_INFO(
"execution time = %gms", t * 1000. / cv::getTickFrequency());
235 cv::Mat wshed(markers.size(), CV_8UC3);
238 for (i = 0; i < markers.rows; i++)
239 for (j = 0; j < markers.cols; j++)
241 int index = markers.at<
int>(i, j);
243 wshed.at<cv::Vec3b>(i, j) = cv::Vec3b(255, 255, 255);
244 else if (index <= 0 || index > comp_count)
245 wshed.at<cv::Vec3b>(i, j) = cv::Vec3b(0, 0, 0);
247 wshed.at<cv::Vec3b>(i, j) = color_tab[index - 1];
250 wshed = wshed * 0.5 + img_gray * 0.5;
255 cv::imshow(segment_name_, wshed);
257 int c = cv::waitKey(1);
262 markerMask = cv::Scalar::all(0);
269 msg_pub_.
publish(contours_msg);
271 catch (cv::Exception& e)
273 NODELET_ERROR(
"Image processing error: %s %s %s %i", e.err.c_str(), e.func.c_str(), e.file.c_str(), e.line);
276 prev_stamp_ = msg->header.stamp;
281 if (msg.points.empty())
283 markerMask = cv::Scalar::all(0);
287 for (
const opencv_apps::Point2D& point : msg.points)
289 cv::Point pt0(point.x, point.y);
290 cv::Point pt1(pt0.x + 1, pt0.y + 1);
291 cv::line(markerMask, pt0, pt1, cv::Scalar::all(255), 5, 8, 0);
299 if (config_.use_camera_info)
318 pnh_->param(
"queue_size", queue_size_, 3);
319 pnh_->param(
"debug_view", debug_view_,
false);
326 window_name_ =
"roughly mark the areas to segment on the image";
327 segment_name_ =
"watershed transform";
331 reconfigure_server_ = boost::make_shared<dynamic_reconfigure::Server<Config> >(*pnh_);
332 dynamic_reconfigure::Server<Config>::CallbackType
f =
334 reconfigure_server_->setCallback(f);
338 msg_pub_ = advertise<opencv_apps::ContourArrayStamped>(*
pnh_,
"contours", 1);
340 NODELET_INFO(
"This program demonstrates the famous watershed segmentation algorithm in OpenCV: watershed()");
341 NODELET_INFO(
"Hot keys: ");
342 NODELET_INFO(
"\tESC - quit the program");
343 NODELET_INFO(
"\tr - restore the original image");
344 NODELET_INFO(
"\tw or SPACE - run watershed segmentation algorithm");
345 NODELET_INFO(
"\t\t(before running it, *roughly* mark the areas to segment on the image)");
346 NODELET_INFO(
"\t (before that, roughly outline several markers on the image)");
366 ROS_WARN(
"DeprecationWarning: Nodelet watershed_segmentation/watershed_segmentation is deprecated, " 367 "and renamed to opencv_apps/watershed_segmentation.");
static void onMouse(int event, int x, int y, int flags, void *)
CvImageConstPtr toCvShare(const sensor_msgs::ImageConstPtr &source, const std::string &encoding=std::string())
std::string segment_name_
image_transport::CameraSubscriber cam_sub_
#define NODELET_ERROR(...)
virtual void onInit()
Initialize nodehandles nh_ and pnh_. Subclass should call this method in its onInit method...
#define NODELET_WARN(...)
void publish(const boost::shared_ptr< M > &message) const
opencv_apps::WatershedSegmentationConfig Config
Nodelet to automatically subscribe/unsubscribe topics according to subscription of advertised topics...
Demo code to calculate moments.
virtual void onInit()
Initialize nodehandles nh_ and pnh_. Subclass should call this method in its onInit method...
void unsubscribe()
This method is called when publisher is unsubscribed by other nodes. Shut down subscribers in this me...
boost::shared_ptr< ros::NodeHandle > pnh_
Shared pointer to private nodehandle.
static bool need_config_update_
static int on_mouse_event_
image_transport::Publisher img_pub_
static bool on_mouse_update_
image_transport::Subscriber img_sub_
bool always_subscribe_
A flag to disable watching mechanism and always subscribe input topics. It can be specified via ~alwa...
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...
void publish(const sensor_msgs::Image &message) const
void doWork(const sensor_msgs::ImageConstPtr &msg, const std::string &input_frame_from_msg)
void imageCallbackWithInfo(const sensor_msgs::ImageConstPtr &msg, const sensor_msgs::CameraInfoConstPtr &cam_info)
boost::shared_ptr< ros::NodeHandle > nh_
Shared pointer to nodehandle.
void imageCallback(const sensor_msgs::ImageConstPtr &msg)
void reconfigureCallback(opencv_apps::WatershedSegmentationConfig &new_config, uint32_t level)
void addSeedPointCb(const opencv_apps::Point2DArray &msg)
static int on_mouse_flags_
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...
#define NODELET_INFO(...)
PLUGINLIB_EXPORT_CLASS(opencv_apps::WatershedSegmentationNodelet, nodelet::Nodelet)
static void trackbarCallback(int, void *)
boost::shared_ptr< ReconfigureServer > reconfigure_server_
void subscribe()
This method is called when publisher is subscribed by other nodes. Set up subscribers in this method...
#define NODELET_DEBUG(...)
dynamic_reconfigure::Server< Config > ReconfigureServer
const std::string & frameWithDefault(const std::string &frame, const std::string &image_frame)
sensor_msgs::ImagePtr toImageMsg() const
ros::Subscriber add_seed_points_sub_
boost::shared_ptr< image_transport::ImageTransport > it_