segment_objects_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/segment_objects.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 #include <opencv2/video/background_segm.hpp>
00049 
00050 #include <dynamic_reconfigure/server.h>
00051 #include "opencv_apps/SegmentObjectsConfig.h"
00052 #include "std_srvs/Empty.h"
00053 #include "std_msgs/Float64.h"
00054 #include "opencv_apps/Contour.h"
00055 #include "opencv_apps/ContourArray.h"
00056 #include "opencv_apps/ContourArrayStamped.h"
00057 
00058 namespace segment_objects {
00059 class SegmentObjectsNodelet : public opencv_apps::Nodelet
00060 {
00061   image_transport::Publisher img_pub_;
00062   image_transport::Subscriber img_sub_;
00063   image_transport::CameraSubscriber cam_sub_;
00064   ros::Publisher msg_pub_, area_pub_;
00065   ros::ServiceServer update_bg_model_service_;
00066 
00067   boost::shared_ptr<image_transport::ImageTransport> it_;
00068 
00069   typedef segment_objects::SegmentObjectsConfig Config;
00070   typedef dynamic_reconfigure::Server<Config> ReconfigureServer;
00071   Config config_;
00072   boost::shared_ptr<ReconfigureServer> reconfigure_server_;
00073 
00074   bool debug_view_;
00075   ros::Time prev_stamp_;
00076 
00077   std::string window_name_;
00078   static bool need_config_update_;
00079 
00080 #ifndef CV_VERSION_EPOCH
00081   cv::Ptr<cv::BackgroundSubtractorMOG2> bgsubtractor;
00082 #else
00083   cv::BackgroundSubtractorMOG bgsubtractor;
00084 #endif
00085   bool update_bg_model;
00086 
00087   void reconfigureCallback(Config &new_config, uint32_t level)
00088   {
00089     config_ = new_config;
00090   }
00091 
00092   const std::string &frameWithDefault(const std::string &frame, const std::string &image_frame)
00093   {
00094     if (frame.empty())
00095       return image_frame;
00096     return frame;
00097   }
00098 
00099   void imageCallbackWithInfo(const sensor_msgs::ImageConstPtr& msg, const sensor_msgs::CameraInfoConstPtr& cam_info)
00100   {
00101     do_work(msg, cam_info->header.frame_id);
00102   }
00103   
00104   void imageCallback(const sensor_msgs::ImageConstPtr& msg)
00105   {
00106     do_work(msg, msg->header.frame_id);
00107   }
00108 
00109   static void trackbarCallback( int, void* )
00110   {
00111     need_config_update_ = true;
00112   }
00113 
00114   void do_work(const sensor_msgs::ImageConstPtr& msg, const std::string input_frame_from_msg)
00115   {
00116     // Work on the image.
00117     try
00118     {
00119       // Convert the image into something opencv can handle.
00120       cv::Mat frame = cv_bridge::toCvShare(msg, sensor_msgs::image_encodings::BGR8)->image;
00121 
00122       // Messages
00123       opencv_apps::ContourArrayStamped contours_msg;
00124       contours_msg.header = msg->header;
00125 
00126       // Do the work
00127       cv::Mat bgmask, out_frame;
00128 
00129       if( debug_view_) {
00131         cv::namedWindow( window_name_, cv::WINDOW_AUTOSIZE );
00132         if (need_config_update_) {
00133           reconfigure_server_->updateConfig(config_);
00134           need_config_update_ = false;
00135         }
00136       }
00137 
00138 #ifndef CV_VERSION_EPOCH
00139       bgsubtractor->apply(frame, bgmask, update_bg_model ? -1 : 0);
00140 #else
00141       bgsubtractor(frame, bgmask, update_bg_model ? -1 : 0);
00142 #endif
00143       //refineSegments(tmp_frame, bgmask, out_frame);
00144       int niters = 3;
00145 
00146       std::vector<std::vector<cv::Point> > contours;
00147       std::vector<cv::Vec4i> hierarchy;
00148 
00149       cv::Mat temp;
00150 
00151       cv::dilate(bgmask, temp, cv::Mat(), cv::Point(-1,-1), niters);
00152       cv::erode(temp, temp, cv::Mat(), cv::Point(-1,-1), niters*2);
00153       cv::dilate(temp, temp, cv::Mat(), cv::Point(-1,-1), niters);
00154 
00155       cv::findContours( temp, contours, hierarchy, CV_RETR_CCOMP, CV_CHAIN_APPROX_SIMPLE );
00156 
00157       out_frame = cv::Mat::zeros(frame.size(), CV_8UC3);
00158 
00159       if( contours.size() == 0 )
00160         return;
00161 
00162       // iterate through all the top-level contours,
00163       // draw each connected component with its own random color
00164       int idx = 0, largestComp = 0;
00165       double maxArea = 0;
00166 
00167       for( ; idx >= 0; idx = hierarchy[idx][0] )
00168       {
00169         const std::vector<cv::Point>& c = contours[idx];
00170         double area = fabs(cv::contourArea(cv::Mat(c)));
00171         if( area > maxArea )
00172         {
00173           maxArea = area;
00174           largestComp = idx;
00175         }
00176       }
00177       cv::Scalar color( 0, 0, 255 );
00178       cv::drawContours( out_frame, contours, largestComp, color, CV_FILLED, 8, hierarchy );
00179 
00180       std_msgs::Float64 area_msg;
00181       area_msg.data = maxArea;
00182       for( size_t i = 0; i< contours.size(); i++ ) {
00183         opencv_apps::Contour contour_msg;
00184         for ( size_t j = 0; j < contours[i].size(); j++ ) {
00185           opencv_apps::Point2D point_msg;
00186           point_msg.x = contours[i][j].x;
00187           point_msg.y = contours[i][j].y;
00188           contour_msg.points.push_back(point_msg);
00189         }
00190         contours_msg.contours.push_back(contour_msg);
00191       }
00192 
00193       //-- Show what you got
00194       if( debug_view_) {
00195         cv::imshow( window_name_, out_frame );
00196         int keycode = cv::waitKey(1);
00197         //if( keycode == 27 )
00198         //    break;
00199         if( keycode == ' ' )
00200         {
00201             update_bg_model = !update_bg_model;
00202             NODELET_INFO("Learn background is in state = %d",update_bg_model);
00203         }
00204       }
00205 
00206       // Publish the image.
00207       sensor_msgs::Image::Ptr out_img = cv_bridge::CvImage(msg->header, sensor_msgs::image_encodings::BGR8, out_frame).toImageMsg();
00208       img_pub_.publish(out_img);
00209       msg_pub_.publish(contours_msg);
00210       area_pub_.publish(area_msg);
00211     }
00212     catch (cv::Exception &e)
00213     {
00214       NODELET_ERROR("Image processing error: %s %s %s %i", e.err.c_str(), e.func.c_str(), e.file.c_str(), e.line);
00215     }
00216 
00217     prev_stamp_ = msg->header.stamp;
00218   }
00219   
00220   bool update_bg_model_cb(std_srvs::Empty::Request& request, std_srvs::Empty::Response& response) {
00221     update_bg_model = !update_bg_model;
00222     NODELET_INFO("Learn background is in state = %d",update_bg_model);
00223     return true;
00224   }
00225 
00226   void subscribe()
00227   {
00228     NODELET_DEBUG("Subscribing to image topic.");
00229     if (config_.use_camera_info)
00230       cam_sub_ = it_->subscribeCamera("image", 3, &SegmentObjectsNodelet::imageCallbackWithInfo, this);
00231     else
00232       img_sub_ = it_->subscribe("image", 3, &SegmentObjectsNodelet::imageCallback, this);
00233   }
00234 
00235   void unsubscribe()
00236   {
00237     NODELET_DEBUG("Unsubscribing from image topic.");
00238     img_sub_.shutdown();
00239     cam_sub_.shutdown();
00240   }
00241 
00242 public:
00243   virtual void onInit()
00244   {
00245     Nodelet::onInit();
00246     it_ = boost::shared_ptr<image_transport::ImageTransport>(new image_transport::ImageTransport(*nh_));
00247 
00248     pnh_->param("debug_view", debug_view_, false);
00249     if (debug_view_) {
00250       always_subscribe_ = true;
00251     }
00252     prev_stamp_ = ros::Time(0, 0);
00253 
00254     window_name_ = "segmented";
00255     update_bg_model = true;
00256 
00257 #ifndef CV_VERSION_EPOCH
00258     bgsubtractor = cv::createBackgroundSubtractorMOG2();
00259 #else
00260     bgsubtractor.set("noiseSigma", 10);
00261 #endif
00262 
00263     reconfigure_server_ = boost::make_shared<dynamic_reconfigure::Server<Config> >(*pnh_);
00264     dynamic_reconfigure::Server<Config>::CallbackType f =
00265       boost::bind(&SegmentObjectsNodelet::reconfigureCallback, this, _1, _2);
00266     reconfigure_server_->setCallback(f);
00267     
00268     img_pub_ = advertiseImage(*pnh_, "image", 1);
00269     msg_pub_ = advertise<opencv_apps::ContourArrayStamped>(*pnh_, "contours", 1);
00270     area_pub_ = advertise<std_msgs::Float64>(*pnh_, "area", 1);
00271     update_bg_model_service_ = pnh_->advertiseService("update_bg_model", &SegmentObjectsNodelet::update_bg_model_cb, this);
00272 
00273     onInitPostProcess();
00274   }
00275 };
00276 bool SegmentObjectsNodelet::need_config_update_ = false;
00277 }
00278 
00279 #include <pluginlib/class_list_macros.h>
00280 PLUGINLIB_EXPORT_CLASS(segment_objects::SegmentObjectsNodelet, nodelet::Nodelet);


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