watershed_segmentation_nodelet.cpp
Go to the documentation of this file.
00001 /*********************************************************************
00002 * Software License Agreement (BSD License)
00003 *
00004 *  Copyright (c) 2014, Kei Okada.
00005 *  All rights reserved.
00006 * 
00007 *  Redistribution and use in source and binary forms, with or without
00008 *  modification, are permitted provided that the following conditions
00009 *  are met:
00010 * 
00011 *   * Redistributions of source code must retain the above copyright
00012 *     notice, this list of conditions and the following disclaimer.
00013 *   * Redistributions in binary form must reproduce the above
00014 *     copyright notice, this list of conditions and the following
00015 *     disclaimer in the documentation and/or other materials provided
00016 *     with the distribution.
00017 *   * Neither the name of the Kei Okada nor the names of its
00018 *     contributors may be used to endorse or promote products derived
00019 *     from this software without specific prior written permission.
00020 * 
00021 *  THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
00022 *  "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
00023 *  LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
00024 *  FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
00025 *  COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
00026 *  INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
00027 *  BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
00028 *  LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
00029 *  CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
00030 *  LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
00031 *  ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
00032 *  POSSIBILITY OF SUCH DAMAGE.
00033 *********************************************************************/
00034 
00035 // https://github.com/Itseez/opencv/blob/2.4/samples/cpp/watershed.cpp
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 watershed_segmentation {
00057 class WatershedSegmentationNodelet : public opencv_apps::Nodelet
00058 {
00059   image_transport::Publisher img_pub_;
00060   image_transport::Subscriber img_sub_;
00061   image_transport::CameraSubscriber cam_sub_;
00062   ros::Publisher msg_pub_;
00063   ros::Subscriber add_seed_points_sub_;
00064 
00065   boost::shared_ptr<image_transport::ImageTransport> it_;
00066 
00067   typedef watershed_segmentation::WatershedSegmentationConfig Config;
00068   typedef dynamic_reconfigure::Server<Config> ReconfigureServer;
00069   Config config_;
00070   boost::shared_ptr<ReconfigureServer> reconfigure_server_;
00071 
00072   bool debug_view_;
00073   ros::Time prev_stamp_;
00074 
00075   std::string window_name_, segment_name_;
00076   static bool need_config_update_;
00077   static bool on_mouse_update_;
00078   static int on_mouse_event_;
00079   static int on_mouse_x_;
00080   static int on_mouse_y_;
00081   static int on_mouse_flags_;
00082 
00083   cv::Mat markerMask;
00084   cv::Point prevPt;
00085 
00086   static void onMouse( int event, int x, int y, int flags, void* )
00087   {
00088     on_mouse_update_ = true;
00089     on_mouse_event_ = event;
00090     on_mouse_x_ = x;
00091     on_mouse_y_ = y;
00092     on_mouse_flags_ = flags;
00093   }
00094 
00095   void reconfigureCallback(watershed_segmentation::WatershedSegmentationConfig &new_config, uint32_t level)
00096   {
00097     config_ = new_config;
00098   }
00099 
00100   const std::string &frameWithDefault(const std::string &frame, const std::string &image_frame)
00101   {
00102     if (frame.empty())
00103       return image_frame;
00104     return frame;
00105   }
00106 
00107   void imageCallbackWithInfo(const sensor_msgs::ImageConstPtr& msg, const sensor_msgs::CameraInfoConstPtr& cam_info)
00108   {
00109     do_work(msg, cam_info->header.frame_id);
00110   }
00111   
00112   void imageCallback(const sensor_msgs::ImageConstPtr& msg)
00113   {
00114     do_work(msg, msg->header.frame_id);
00115   }
00116 
00117   static void trackbarCallback( int, void* )
00118   {
00119     need_config_update_ = true;
00120   }
00121 
00122   void do_work(const sensor_msgs::ImageConstPtr& msg, const std::string input_frame_from_msg)
00123   {
00124     // Work on the image.
00125     try
00126     {
00127       // Convert the image into something opencv can handle.
00128       cv::Mat frame = cv_bridge::toCvShare(msg, sensor_msgs::image_encodings::BGR8)->image;
00129 
00130       // Messages
00131       opencv_apps::ContourArrayStamped contours_msg;
00132       contours_msg.header = msg->header;
00133 
00134       // Do the work
00135       //std::vector<cv::Rect> faces;
00136       cv::Mat imgGray;
00137 
00139       if ( markerMask.empty() )  {
00140         cv::cvtColor(frame, markerMask, cv::COLOR_BGR2GRAY);
00141         cv::cvtColor(markerMask, imgGray, cv::COLOR_GRAY2BGR);
00142         markerMask = cv::Scalar::all(0);
00143       }
00144 
00145       if( debug_view_) {
00146         cv::imshow( window_name_, frame);
00147         cv::setMouseCallback( window_name_, onMouse, 0 );
00148         if (need_config_update_) {
00149           reconfigure_server_->updateConfig(config_);
00150           need_config_update_ = false;
00151         }
00152 
00153         if ( on_mouse_update_ ) {
00154           int event = on_mouse_event_;
00155           int x = on_mouse_x_;
00156           int y = on_mouse_y_;
00157           int flags = on_mouse_flags_;
00158 
00159           if( x < 0 || x >= frame.cols || y < 0 || y >= frame.rows )
00160             return;
00161           if( event == cv::EVENT_LBUTTONUP || !(flags & cv::EVENT_FLAG_LBUTTON) )
00162             prevPt = cv::Point(-1,-1);
00163           else if( event == cv::EVENT_LBUTTONDOWN )
00164             prevPt = cv::Point(x,y);
00165           else if( event == cv::EVENT_MOUSEMOVE && (flags & cv::EVENT_FLAG_LBUTTON) )
00166           {
00167             cv::Point pt(x, y);
00168             if( prevPt.x < 0 )
00169               prevPt = pt;
00170             cv::line( markerMask, prevPt, pt, cv::Scalar::all(255), 5, 8, 0 );
00171             cv::line( frame, prevPt, pt, cv::Scalar::all(255), 5, 8, 0 );
00172             prevPt = pt;
00173             cv::imshow(window_name_, markerMask);
00174           }
00175         }
00176         cv::waitKey(1);
00177       }
00178       
00179       int i, j, compCount = 0;
00180       std::vector<std::vector<cv::Point> > contours;
00181       std::vector<cv::Vec4i> hierarchy;
00182 
00183       cv::findContours(markerMask, contours, hierarchy, CV_RETR_CCOMP, CV_CHAIN_APPROX_SIMPLE);
00184 
00185       if( contours.empty() ) {
00186         NODELET_WARN("contours are empty");
00187         return; //continue;
00188       }
00189       cv::Mat markers(markerMask.size(), CV_32S);
00190       markers = cv::Scalar::all(0);
00191       int idx = 0;
00192       for( ; idx >= 0; idx = hierarchy[idx][0], compCount++ )
00193         cv::drawContours(markers, contours, idx, cv::Scalar::all(compCount+1), -1, 8, hierarchy, INT_MAX);
00194 
00195       if( compCount == 0 ) {
00196         NODELET_WARN("compCount is 0");
00197         return; //continue;
00198       }
00199       for( size_t i = 0; i< contours.size(); i++ ) {
00200         opencv_apps::Contour contour_msg;
00201         for ( size_t j = 0; j < contours[i].size(); j++ ) {
00202           opencv_apps::Point2D point_msg;
00203           point_msg.x = contours[i][j].x;
00204           point_msg.y = contours[i][j].y;
00205           contour_msg.points.push_back(point_msg);
00206         }
00207         contours_msg.contours.push_back(contour_msg);
00208       }
00209 
00210       std::vector<cv::Vec3b> colorTab;
00211       for( i = 0; i < compCount; i++ )
00212       {
00213         int b = cv::theRNG().uniform(0, 255);
00214         int g = cv::theRNG().uniform(0, 255);
00215         int r = cv::theRNG().uniform(0, 255);
00216 
00217         colorTab.push_back(cv::Vec3b((uchar)b, (uchar)g, (uchar)r));
00218       }
00219 
00220       double t = (double)cv::getTickCount();
00221       cv::watershed( frame, markers );
00222       t = (double)cv::getTickCount() - t;
00223       NODELET_INFO( "execution time = %gms", t*1000./cv::getTickFrequency() );
00224 
00225       cv::Mat wshed(markers.size(), CV_8UC3);
00226 
00227       // paint the watershed image
00228       for( i = 0; i < markers.rows; i++ )
00229         for( j = 0; j < markers.cols; j++ )
00230         {
00231           int index = markers.at<int>(i,j);
00232           if( index == -1 )
00233             wshed.at<cv::Vec3b>(i,j) = cv::Vec3b(255,255,255);
00234           else if( index <= 0 || index > compCount )
00235             wshed.at<cv::Vec3b>(i,j) = cv::Vec3b(0,0,0);
00236           else
00237             wshed.at<cv::Vec3b>(i,j) = colorTab[index - 1];
00238         }
00239 
00240       wshed = wshed*0.5 + imgGray*0.5;
00241 
00242       //-- Show what you got
00243       if( debug_view_) {
00244         cv::imshow( segment_name_, wshed );
00245 
00246         int c = cv::waitKey(1);
00247         //if( (char)c == 27 )
00248         //    break;
00249         if( (char)c == 'r' )
00250         {
00251           markerMask = cv::Scalar::all(0);
00252         }
00253       }
00254 
00255       // Publish the image.
00256       sensor_msgs::Image::Ptr out_img = cv_bridge::CvImage(msg->header, msg->encoding, wshed).toImageMsg();
00257       img_pub_.publish(out_img);
00258       msg_pub_.publish(contours_msg);
00259     }
00260     catch (cv::Exception &e)
00261     {
00262       NODELET_ERROR("Image processing error: %s %s %s %i", e.err.c_str(), e.func.c_str(), e.file.c_str(), e.line);
00263     }
00264 
00265     prev_stamp_ = msg->header.stamp;
00266   }
00267 
00268   void add_seed_point_cb(const opencv_apps::Point2DArray& msg) {
00269     if ( msg.points.size() == 0 ) {
00270       markerMask = cv::Scalar::all(0);
00271     } else {
00272       for(size_t i = 0; i < msg.points.size(); i++ ) {
00273         cv::Point pt0(msg.points[i].x, msg.points[i].y);
00274         cv::Point pt1(pt0.x + 1, pt0.y + 1);
00275         cv::line( markerMask, pt0, pt1, cv::Scalar::all(255), 5, 8, 0 );
00276       }
00277     }
00278   }
00279 
00280   void subscribe()
00281   {
00282     NODELET_DEBUG("Subscribing to image topic.");
00283     if (config_.use_camera_info)
00284       cam_sub_ = it_->subscribeCamera("image", 3, &WatershedSegmentationNodelet::imageCallbackWithInfo, this);
00285     else
00286       img_sub_ = it_->subscribe("image", 3, &WatershedSegmentationNodelet::imageCallback, this);
00287   }
00288 
00289   void unsubscribe()
00290   {
00291     NODELET_DEBUG("Unsubscribing from image topic.");
00292     img_sub_.shutdown();
00293     cam_sub_.shutdown();
00294   }
00295 
00296 public:
00297   virtual void onInit()
00298   {
00299     Nodelet::onInit();
00300     it_ = boost::shared_ptr<image_transport::ImageTransport>(new image_transport::ImageTransport(*nh_));
00301 
00302     pnh_->param("debug_view", debug_view_, false);
00303     if (debug_view_) {
00304       always_subscribe_ = true;
00305     }
00306     prev_stamp_ = ros::Time(0, 0);
00307 
00308     window_name_ = "roughly mark the areas to segment on the image";
00309     segment_name_ = "watershed transform";
00310     prevPt.x = -1;
00311     prevPt.y = -1;
00312 
00313     reconfigure_server_ = boost::make_shared<dynamic_reconfigure::Server<Config> >(*pnh_);
00314     dynamic_reconfigure::Server<Config>::CallbackType f =
00315       boost::bind(&WatershedSegmentationNodelet::reconfigureCallback, this, _1, _2);
00316     reconfigure_server_->setCallback(f);
00317 
00318     add_seed_points_sub_ = pnh_->subscribe("add_seed_points", 1, &WatershedSegmentationNodelet::add_seed_point_cb, this);
00319     img_pub_ = advertiseImage(*pnh_, "image", 1);
00320     msg_pub_ = advertise<opencv_apps::ContourArrayStamped>(*pnh_, "contours", 1);
00321     
00322 
00323     NODELET_INFO("This program demonstrates the famous watershed segmentation algorithm in OpenCV: watershed()");
00324     NODELET_INFO("Hot keys: ");
00325     NODELET_INFO("\tESC - quit the program");
00326     NODELET_INFO("\tr - restore the original image");
00327     NODELET_INFO("\tw or SPACE - run watershed segmentation algorithm");
00328     NODELET_INFO("\t\t(before running it, *roughly* mark the areas to segment on the image)");
00329     NODELET_INFO("\t  (before that, roughly outline several markers on the image)");
00330 
00331     onInitPostProcess();
00332   }
00333 };
00334 bool WatershedSegmentationNodelet::need_config_update_ = false;
00335 bool WatershedSegmentationNodelet::on_mouse_update_ = false;
00336 int WatershedSegmentationNodelet::on_mouse_event_ = 0;
00337 int WatershedSegmentationNodelet::on_mouse_x_ = 0;
00338 int WatershedSegmentationNodelet::on_mouse_y_ = 0;
00339 int WatershedSegmentationNodelet::on_mouse_flags_ = 0;
00340 }
00341 
00342 #include <pluginlib/class_list_macros.h>
00343 PLUGINLIB_EXPORT_CLASS(watershed_segmentation::WatershedSegmentationNodelet, nodelet::Nodelet);


opencv_apps
Author(s): Kei Okada
autogenerated on Tue May 2 2017 02:58:59