00001
00002
00003
00004
00005
00006
00007
00008
00009
00010
00011
00012
00013
00014
00015
00016
00017
00018
00019
00020
00021
00022
00023
00024
00025
00026
00027
00028
00029
00030
00031
00032
00033
00034
00035
00040 #include <ros/ros.h>
00041 #include "opencv_apps/nodelet.h"
00042 #include <image_transport/image_transport.h>
00043 #include <cv_bridge/cv_bridge.h>
00044 #include <sensor_msgs/image_encodings.h>
00045
00046 #include <opencv2/highgui/highgui.hpp>
00047 #include <opencv2/imgproc/imgproc.hpp>
00048
00049 #include <dynamic_reconfigure/server.h>
00050 #include "opencv_apps/WatershedSegmentationConfig.h"
00051 #include "opencv_apps/Contour.h"
00052 #include "opencv_apps/ContourArray.h"
00053 #include "opencv_apps/ContourArrayStamped.h"
00054 #include "opencv_apps/Point2DArray.h"
00055
00056 namespace opencv_apps
00057 {
00058 class WatershedSegmentationNodelet : public opencv_apps::Nodelet
00059 {
00060 image_transport::Publisher img_pub_;
00061 image_transport::Subscriber img_sub_;
00062 image_transport::CameraSubscriber cam_sub_;
00063 ros::Publisher msg_pub_;
00064 ros::Subscriber add_seed_points_sub_;
00065
00066 boost::shared_ptr<image_transport::ImageTransport> it_;
00067
00068 typedef opencv_apps::WatershedSegmentationConfig Config;
00069 typedef dynamic_reconfigure::Server<Config> ReconfigureServer;
00070 Config config_;
00071 boost::shared_ptr<ReconfigureServer> reconfigure_server_;
00072
00073 int queue_size_;
00074 bool debug_view_;
00075 ros::Time prev_stamp_;
00076
00077 std::string window_name_, segment_name_;
00078 static bool need_config_update_;
00079 static bool on_mouse_update_;
00080 static int on_mouse_event_;
00081 static int on_mouse_x_;
00082 static int on_mouse_y_;
00083 static int on_mouse_flags_;
00084
00085 cv::Mat markerMask;
00086 cv::Point prevPt;
00087
00088 static void onMouse(int event, int x, int y, int flags, void* )
00089 {
00090 on_mouse_update_ = true;
00091 on_mouse_event_ = event;
00092 on_mouse_x_ = x;
00093 on_mouse_y_ = y;
00094 on_mouse_flags_ = flags;
00095 }
00096
00097 void reconfigureCallback(opencv_apps::WatershedSegmentationConfig& new_config, uint32_t level)
00098 {
00099 config_ = new_config;
00100 }
00101
00102 const std::string& frameWithDefault(const std::string& frame, const std::string& image_frame)
00103 {
00104 if (frame.empty())
00105 return image_frame;
00106 return frame;
00107 }
00108
00109 void imageCallbackWithInfo(const sensor_msgs::ImageConstPtr& msg, const sensor_msgs::CameraInfoConstPtr& cam_info)
00110 {
00111 doWork(msg, cam_info->header.frame_id);
00112 }
00113
00114 void imageCallback(const sensor_msgs::ImageConstPtr& msg)
00115 {
00116 doWork(msg, msg->header.frame_id);
00117 }
00118
00119 static void trackbarCallback(int , void* )
00120 {
00121 need_config_update_ = true;
00122 }
00123
00124 void doWork(const sensor_msgs::ImageConstPtr& msg, const std::string& input_frame_from_msg)
00125 {
00126
00127 try
00128 {
00129
00130 cv::Mat frame = cv_bridge::toCvShare(msg, sensor_msgs::image_encodings::BGR8)->image;
00131
00132
00133 opencv_apps::ContourArrayStamped contours_msg;
00134 contours_msg.header = msg->header;
00135
00136
00137
00138 cv::Mat img_gray;
00139
00141 if (markerMask.empty())
00142 {
00143 cv::cvtColor(frame, markerMask, cv::COLOR_BGR2GRAY);
00144 cv::cvtColor(markerMask, img_gray, cv::COLOR_GRAY2BGR);
00145 markerMask = cv::Scalar::all(0);
00146 }
00147
00148 if (debug_view_)
00149 {
00150 cv::imshow(window_name_, frame);
00151 cv::setMouseCallback(window_name_, onMouse, nullptr);
00152 if (need_config_update_)
00153 {
00154 reconfigure_server_->updateConfig(config_);
00155 need_config_update_ = false;
00156 }
00157
00158 if (on_mouse_update_)
00159 {
00160 int event = on_mouse_event_;
00161 int x = on_mouse_x_;
00162 int y = on_mouse_y_;
00163 int flags = on_mouse_flags_;
00164
00165 if (x < 0 || x >= frame.cols || y < 0 || y >= frame.rows)
00166 return;
00167 if (event == cv::EVENT_LBUTTONUP || !(flags & cv::EVENT_FLAG_LBUTTON))
00168 prevPt = cv::Point(-1, -1);
00169 else if (event == cv::EVENT_LBUTTONDOWN)
00170 prevPt = cv::Point(x, y);
00171 else if (event == cv::EVENT_MOUSEMOVE && (flags & cv::EVENT_FLAG_LBUTTON))
00172 {
00173 cv::Point pt(x, y);
00174 if (prevPt.x < 0)
00175 prevPt = pt;
00176 cv::line(markerMask, prevPt, pt, cv::Scalar::all(255), 5, 8, 0);
00177 cv::line(frame, prevPt, pt, cv::Scalar::all(255), 5, 8, 0);
00178 prevPt = pt;
00179 cv::imshow(window_name_, markerMask);
00180 }
00181 }
00182 cv::waitKey(1);
00183 }
00184
00185 int i, j, comp_count = 0;
00186 std::vector<std::vector<cv::Point> > contours;
00187 std::vector<cv::Vec4i> hierarchy;
00188
00189 cv::findContours(markerMask, contours, hierarchy, CV_RETR_CCOMP, CV_CHAIN_APPROX_SIMPLE);
00190
00191 if (contours.empty())
00192 {
00193 NODELET_WARN("contours are empty");
00194 return;
00195 }
00196 cv::Mat markers(markerMask.size(), CV_32S);
00197 markers = cv::Scalar::all(0);
00198 int idx = 0;
00199 for (; idx >= 0; idx = hierarchy[idx][0], comp_count++)
00200 cv::drawContours(markers, contours, idx, cv::Scalar::all(comp_count + 1), -1, 8, hierarchy, INT_MAX);
00201
00202 if (comp_count == 0)
00203 {
00204 NODELET_WARN("compCount is 0");
00205 return;
00206 }
00207 for (const std::vector<cv::Point>& contour : contours)
00208 {
00209 opencv_apps::Contour contour_msg;
00210 for (const cv::Point& j : contour)
00211 {
00212 opencv_apps::Point2D point_msg;
00213 point_msg.x = j.x;
00214 point_msg.y = j.y;
00215 contour_msg.points.push_back(point_msg);
00216 }
00217 contours_msg.contours.push_back(contour_msg);
00218 }
00219
00220 std::vector<cv::Vec3b> color_tab;
00221 for (i = 0; i < comp_count; i++)
00222 {
00223 int b = cv::theRNG().uniform(0, 255);
00224 int g = cv::theRNG().uniform(0, 255);
00225 int r = cv::theRNG().uniform(0, 255);
00226
00227 color_tab.push_back(cv::Vec3b((uchar)b, (uchar)g, (uchar)r));
00228 }
00229
00230 double t = (double)cv::getTickCount();
00231 cv::watershed(frame, markers);
00232 t = (double)cv::getTickCount() - t;
00233 NODELET_INFO("execution time = %gms", t * 1000. / cv::getTickFrequency());
00234
00235 cv::Mat wshed(markers.size(), CV_8UC3);
00236
00237
00238 for (i = 0; i < markers.rows; i++)
00239 for (j = 0; j < markers.cols; j++)
00240 {
00241 int index = markers.at<int>(i, j);
00242 if (index == -1)
00243 wshed.at<cv::Vec3b>(i, j) = cv::Vec3b(255, 255, 255);
00244 else if (index <= 0 || index > comp_count)
00245 wshed.at<cv::Vec3b>(i, j) = cv::Vec3b(0, 0, 0);
00246 else
00247 wshed.at<cv::Vec3b>(i, j) = color_tab[index - 1];
00248 }
00249
00250 wshed = wshed * 0.5 + img_gray * 0.5;
00251
00252
00253 if (debug_view_)
00254 {
00255 cv::imshow(segment_name_, wshed);
00256
00257 int c = cv::waitKey(1);
00258
00259
00260 if ((char)c == 'r')
00261 {
00262 markerMask = cv::Scalar::all(0);
00263 }
00264 }
00265
00266
00267 sensor_msgs::Image::Ptr out_img = cv_bridge::CvImage(msg->header, msg->encoding, wshed).toImageMsg();
00268 img_pub_.publish(out_img);
00269 msg_pub_.publish(contours_msg);
00270 }
00271 catch (cv::Exception& e)
00272 {
00273 NODELET_ERROR("Image processing error: %s %s %s %i", e.err.c_str(), e.func.c_str(), e.file.c_str(), e.line);
00274 }
00275
00276 prev_stamp_ = msg->header.stamp;
00277 }
00278
00279 void addSeedPointCb(const opencv_apps::Point2DArray& msg)
00280 {
00281 if (msg.points.empty())
00282 {
00283 markerMask = cv::Scalar::all(0);
00284 }
00285 else
00286 {
00287 for (const opencv_apps::Point2D& point : msg.points)
00288 {
00289 cv::Point pt0(point.x, point.y);
00290 cv::Point pt1(pt0.x + 1, pt0.y + 1);
00291 cv::line(markerMask, pt0, pt1, cv::Scalar::all(255), 5, 8, 0);
00292 }
00293 }
00294 }
00295
00296 void subscribe()
00297 {
00298 NODELET_DEBUG("Subscribing to image topic.");
00299 if (config_.use_camera_info)
00300 cam_sub_ = it_->subscribeCamera("image", queue_size_, &WatershedSegmentationNodelet::imageCallbackWithInfo, this);
00301 else
00302 img_sub_ = it_->subscribe("image", queue_size_, &WatershedSegmentationNodelet::imageCallback, this);
00303 }
00304
00305 void unsubscribe()
00306 {
00307 NODELET_DEBUG("Unsubscribing from image topic.");
00308 img_sub_.shutdown();
00309 cam_sub_.shutdown();
00310 }
00311
00312 public:
00313 virtual void onInit()
00314 {
00315 Nodelet::onInit();
00316 it_ = boost::shared_ptr<image_transport::ImageTransport>(new image_transport::ImageTransport(*nh_));
00317
00318 pnh_->param("queue_size", queue_size_, 3);
00319 pnh_->param("debug_view", debug_view_, false);
00320 if (debug_view_)
00321 {
00322 always_subscribe_ = true;
00323 }
00324 prev_stamp_ = ros::Time(0, 0);
00325
00326 window_name_ = "roughly mark the areas to segment on the image";
00327 segment_name_ = "watershed transform";
00328 prevPt.x = -1;
00329 prevPt.y = -1;
00330
00331 reconfigure_server_ = boost::make_shared<dynamic_reconfigure::Server<Config> >(*pnh_);
00332 dynamic_reconfigure::Server<Config>::CallbackType f =
00333 boost::bind(&WatershedSegmentationNodelet::reconfigureCallback, this, _1, _2);
00334 reconfigure_server_->setCallback(f);
00335
00336 add_seed_points_sub_ = pnh_->subscribe("add_seed_points", 1, &WatershedSegmentationNodelet::addSeedPointCb, this);
00337 img_pub_ = advertiseImage(*pnh_, "image", 1);
00338 msg_pub_ = advertise<opencv_apps::ContourArrayStamped>(*pnh_, "contours", 1);
00339
00340 NODELET_INFO("This program demonstrates the famous watershed segmentation algorithm in OpenCV: watershed()");
00341 NODELET_INFO("Hot keys: ");
00342 NODELET_INFO("\tESC - quit the program");
00343 NODELET_INFO("\tr - restore the original image");
00344 NODELET_INFO("\tw or SPACE - run watershed segmentation algorithm");
00345 NODELET_INFO("\t\t(before running it, *roughly* mark the areas to segment on the image)");
00346 NODELET_INFO("\t (before that, roughly outline several markers on the image)");
00347
00348 onInitPostProcess();
00349 }
00350 };
00351 bool WatershedSegmentationNodelet::need_config_update_ = false;
00352 bool WatershedSegmentationNodelet::on_mouse_update_ = false;
00353 int WatershedSegmentationNodelet::on_mouse_event_ = 0;
00354 int WatershedSegmentationNodelet::on_mouse_x_ = 0;
00355 int WatershedSegmentationNodelet::on_mouse_y_ = 0;
00356 int WatershedSegmentationNodelet::on_mouse_flags_ = 0;
00357 }
00358
00359 namespace watershed_segmentation
00360 {
00361 class WatershedSegmentationNodelet : public opencv_apps::WatershedSegmentationNodelet
00362 {
00363 public:
00364 virtual void onInit()
00365 {
00366 ROS_WARN("DeprecationWarning: Nodelet watershed_segmentation/watershed_segmentation is deprecated, "
00367 "and renamed to opencv_apps/watershed_segmentation.");
00368 opencv_apps::WatershedSegmentationNodelet::onInit();
00369 }
00370 };
00371 }
00372
00373 #include <pluginlib/class_list_macros.h>
00374 PLUGINLIB_EXPORT_CLASS(opencv_apps::WatershedSegmentationNodelet, nodelet::Nodelet);
00375 PLUGINLIB_EXPORT_CLASS(watershed_segmentation::WatershedSegmentationNodelet, nodelet::Nodelet);