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


opencv_apps
Author(s): Kei Okada
autogenerated on Mon Apr 22 2019 02:18:26