segment_objects_nodelet.cpp
Go to the documentation of this file.
1 /*********************************************************************
2 * Software License Agreement (BSD License)
3 *
4 * Copyright (c) 2014, Kei Okada.
5 * All rights reserved.
6 *
7 * Redistribution and use in source and binary forms, with or without
8 * modification, are permitted provided that the following conditions
9 * are met:
10 *
11 * * Redistributions of source code must retain the above copyright
12 * notice, this list of conditions and the following disclaimer.
13 * * Redistributions in binary form must reproduce the above
14 * copyright notice, this list of conditions and the following
15 * disclaimer in the documentation and/or other materials provided
16 * with the distribution.
17 * * Neither the name of the Kei Okada nor the names of its
18 * contributors may be used to endorse or promote products derived
19 * from this software without specific prior written permission.
20 *
21 * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
22 * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
23 * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
24 * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
25 * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
26 * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
27 * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
28 * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
29 * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
30 * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
31 * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
32 * POSSIBILITY OF SUCH DAMAGE.
33 *********************************************************************/
34 
35 // https://github.com/Itseez/opencv/blob/2.4/samples/cpp/segment_objects.cpp
40 #include <ros/ros.h>
41 #include "opencv_apps/nodelet.h"
43 #include <cv_bridge/cv_bridge.h>
45 
46 #include <opencv2/highgui/highgui.hpp>
47 #include <opencv2/imgproc/imgproc.hpp>
48 #include <opencv2/video/background_segm.hpp>
49 #if CV_MAJOR_VERSION >= 4
50 #include <opencv2/imgproc/imgproc_c.h> // incldue CV_FILLED
51 #endif
52 
53 #include <dynamic_reconfigure/server.h>
54 #include "opencv_apps/SegmentObjectsConfig.h"
55 #include "std_srvs/Empty.h"
56 #include "std_msgs/Float64.h"
57 #include "opencv_apps/Contour.h"
58 #include "opencv_apps/ContourArray.h"
59 #include "opencv_apps/ContourArrayStamped.h"
60 
61 namespace opencv_apps
62 {
64 {
70 
72 
73  typedef opencv_apps::SegmentObjectsConfig Config;
74  typedef dynamic_reconfigure::Server<Config> ReconfigureServer;
75  Config config_;
77 
81 
82  std::string window_name_;
83  static bool need_config_update_;
84 
85 #ifndef CV_VERSION_EPOCH
86  cv::Ptr<cv::BackgroundSubtractorMOG2> bgsubtractor;
87 #else
88  cv::BackgroundSubtractorMOG bgsubtractor;
89 #endif
91 
92  void reconfigureCallback(Config& new_config, uint32_t level)
93  {
94  config_ = new_config;
95  }
96 
97  const std::string& frameWithDefault(const std::string& frame, const std::string& image_frame)
98  {
99  if (frame.empty())
100  return image_frame;
101  return frame;
102  }
103 
104  void imageCallbackWithInfo(const sensor_msgs::ImageConstPtr& msg, const sensor_msgs::CameraInfoConstPtr& cam_info)
105  {
106  doWork(msg, cam_info->header.frame_id);
107  }
108 
109  void imageCallback(const sensor_msgs::ImageConstPtr& msg)
110  {
111  doWork(msg, msg->header.frame_id);
112  }
113 
114  static void trackbarCallback(int /*unused*/, void* /*unused*/)
115  {
116  need_config_update_ = true;
117  }
118 
119  void doWork(const sensor_msgs::ImageConstPtr& msg, const std::string& input_frame_from_msg)
120  {
121  // Work on the image.
122  try
123  {
124  // Convert the image into something opencv can handle.
125  cv::Mat frame = cv_bridge::toCvShare(msg, sensor_msgs::image_encodings::BGR8)->image;
126 
127  // Messages
128  opencv_apps::ContourArrayStamped contours_msg;
129  contours_msg.header = msg->header;
130 
131  // Do the work
132  cv::Mat bgmask, out_frame;
133 
134  if (debug_view_)
135  {
137  cv::namedWindow(window_name_, cv::WINDOW_AUTOSIZE);
138  if (need_config_update_)
139  {
140  reconfigure_server_->updateConfig(config_);
141  need_config_update_ = false;
142  }
143  }
144 
145 #ifndef CV_VERSION_EPOCH
146  bgsubtractor->apply(frame, bgmask, update_bg_model ? -1 : 0);
147 #else
148  bgsubtractor(frame, bgmask, update_bg_model ? -1 : 0);
149 #endif
150  // refineSegments(tmp_frame, bgmask, out_frame);
151  int niters = 3;
152 
153  std::vector<std::vector<cv::Point> > contours;
154  std::vector<cv::Vec4i> hierarchy;
155 
156  cv::Mat temp;
157 
158  cv::dilate(bgmask, temp, cv::Mat(), cv::Point(-1, -1), niters);
159  cv::erode(temp, temp, cv::Mat(), cv::Point(-1, -1), niters * 2);
160  cv::dilate(temp, temp, cv::Mat(), cv::Point(-1, -1), niters);
161 
162  cv::findContours(temp, contours, hierarchy, CV_RETR_CCOMP, CV_CHAIN_APPROX_SIMPLE);
163 
164  out_frame = cv::Mat::zeros(frame.size(), CV_8UC3);
165 
166  if (contours.empty())
167  return;
168 
169  // iterate through all the top-level contours,
170  // draw each connected component with its own random color
171  int idx = 0, largest_comp = 0;
172  double max_area = 0;
173 
174  for (; idx >= 0; idx = hierarchy[idx][0])
175  {
176  const std::vector<cv::Point>& c = contours[idx];
177  double area = fabs(cv::contourArea(cv::Mat(c)));
178  if (area > max_area)
179  {
180  max_area = area;
181  largest_comp = idx;
182  }
183  }
184  cv::Scalar color(0, 0, 255);
185  cv::drawContours(out_frame, contours, largest_comp, color, CV_FILLED, 8, hierarchy);
186 
187  std_msgs::Float64 area_msg;
188  area_msg.data = max_area;
189  for (const std::vector<cv::Point>& contour : contours)
190  {
191  opencv_apps::Contour contour_msg;
192  for (const cv::Point& j : contour)
193  {
194  opencv_apps::Point2D point_msg;
195  point_msg.x = j.x;
196  point_msg.y = j.y;
197  contour_msg.points.push_back(point_msg);
198  }
199  contours_msg.contours.push_back(contour_msg);
200  }
201 
202  //-- Show what you got
203  if (debug_view_)
204  {
205  cv::imshow(window_name_, out_frame);
206  int keycode = cv::waitKey(1);
207  // if( keycode == 27 )
208  // break;
209  if (keycode == ' ')
210  {
211  update_bg_model = !update_bg_model;
212  NODELET_INFO("Learn background is in state = %d", update_bg_model);
213  }
214  }
215 
216  // Publish the image.
217  sensor_msgs::Image::Ptr out_img =
219  img_pub_.publish(out_img);
220  msg_pub_.publish(contours_msg);
221  area_pub_.publish(area_msg);
222  }
223  catch (cv::Exception& e)
224  {
225  NODELET_ERROR("Image processing error: %s %s %s %i", e.err.c_str(), e.func.c_str(), e.file.c_str(), e.line);
226  }
227 
228  prev_stamp_ = msg->header.stamp;
229  }
230 
231  bool updateBgModelCb(std_srvs::Empty::Request& request, std_srvs::Empty::Response& response)
232  {
233  update_bg_model = !update_bg_model;
234  NODELET_INFO("Learn background is in state = %d", update_bg_model);
235  return true;
236  }
237 
238  void subscribe() // NOLINT(modernize-use-override)
239  {
240  NODELET_DEBUG("Subscribing to image topic.");
241  if (config_.use_camera_info)
242  cam_sub_ = it_->subscribeCamera("image", queue_size_, &SegmentObjectsNodelet::imageCallbackWithInfo, this);
243  else
244  img_sub_ = it_->subscribe("image", queue_size_, &SegmentObjectsNodelet::imageCallback, this);
245  }
246 
247  void unsubscribe() // NOLINT(modernize-use-override)
248  {
249  NODELET_DEBUG("Unsubscribing from image topic.");
250  img_sub_.shutdown();
251  cam_sub_.shutdown();
252  }
253 
254 public:
255  virtual void onInit() // NOLINT(modernize-use-override)
256  {
257  Nodelet::onInit();
259 
260  pnh_->param("queue_size", queue_size_, 3);
261  pnh_->param("debug_view", debug_view_, false);
262  if (debug_view_)
263  {
264  always_subscribe_ = true;
265  }
266  prev_stamp_ = ros::Time(0, 0);
267 
268  window_name_ = "segmented";
269  update_bg_model = true;
270 
271 #ifndef CV_VERSION_EPOCH
272  bgsubtractor = cv::createBackgroundSubtractorMOG2();
273 #else
274  bgsubtractor.set("noiseSigma", 10);
275 #endif
276 
277  reconfigure_server_ = boost::make_shared<dynamic_reconfigure::Server<Config> >(*pnh_);
278  dynamic_reconfigure::Server<Config>::CallbackType f =
279  boost::bind(&SegmentObjectsNodelet::reconfigureCallback, this, _1, _2);
280  reconfigure_server_->setCallback(f);
281 
282  img_pub_ = advertiseImage(*pnh_, "image", 1);
283  msg_pub_ = advertise<opencv_apps::ContourArrayStamped>(*pnh_, "contours", 1);
284  area_pub_ = advertise<std_msgs::Float64>(*pnh_, "area", 1);
285  update_bg_model_service_ = pnh_->advertiseService("update_bg_model", &SegmentObjectsNodelet::updateBgModelCb, this);
286 
288  }
289 };
291 } // namespace opencv_apps
292 
294 {
296 {
297 public:
298  virtual void onInit() // NOLINT(modernize-use-override)
299  {
300  ROS_WARN("DeprecationWarning: Nodelet segment_objects/segment_objects is deprecated, "
301  "and renamed to opencv_apps/segment_objects.");
303  }
304 };
305 } // namespace segment_objects
306 
CvImageConstPtr toCvShare(const sensor_msgs::ImageConstPtr &source, const std::string &encoding=std::string())
void imageCallback(const sensor_msgs::ImageConstPtr &msg)
#define NODELET_ERROR(...)
void publish(const boost::shared_ptr< M > &message) const
f
Nodelet to automatically subscribe/unsubscribe topics according to subscription of advertised topics...
Definition: nodelet.h:70
Demo code to calculate moments.
Definition: nodelet.h:48
const std::string & frameWithDefault(const std::string &frame, const std::string &image_frame)
image_transport::CameraSubscriber cam_sub_
void unsubscribe()
This method is called when publisher is unsubscribed by other nodes. Shut down subscribers in this me...
void imageCallbackWithInfo(const sensor_msgs::ImageConstPtr &msg, const sensor_msgs::CameraInfoConstPtr &cam_info)
boost::shared_ptr< ros::NodeHandle > pnh_
Shared pointer to private nodehandle.
Definition: nodelet.h:250
#define ROS_WARN(...)
void subscribe()
This method is called when publisher is subscribed by other nodes. Set up subscribers in this method...
bool always_subscribe_
A flag to disable watching mechanism and always subscribe input topics. It can be specified via ~alwa...
Definition: nodelet.h:273
opencv_apps::SegmentObjectsConfig Config
virtual void onInitPostProcess()
Post processing of initialization of nodelet. You need to call this method in order to use always_sub...
Definition: nodelet.cpp:57
virtual void onInit()
Initialize nodehandles nh_ and pnh_. Subclass should call this method in its onInit method...
Definition: nodelet.cpp:40
void publish(const sensor_msgs::Image &message) const
void doWork(const sensor_msgs::ImageConstPtr &msg, const std::string &input_frame_from_msg)
boost::shared_ptr< ros::NodeHandle > nh_
Shared pointer to nodehandle.
Definition: nodelet.h:245
dynamic_reconfigure::Server< Config > ReconfigureServer
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...
Definition: nodelet.h:180
#define NODELET_INFO(...)
PLUGINLIB_EXPORT_CLASS(opencv_apps::SegmentObjectsNodelet, nodelet::Nodelet)
virtual void onInit()
Initialize nodehandles nh_ and pnh_. Subclass should call this method in its onInit method...
bool updateBgModelCb(std_srvs::Empty::Request &request, std_srvs::Empty::Response &response)
boost::shared_ptr< image_transport::ImageTransport > it_
boost::shared_ptr< ReconfigureServer > reconfigure_server_
virtual void onInit()
Initialize nodehandles nh_ and pnh_. Subclass should call this method in its onInit method...
#define NODELET_DEBUG(...)
sensor_msgs::ImagePtr toImageMsg() const
cv::Ptr< cv::BackgroundSubtractorMOG2 > bgsubtractor
void reconfigureCallback(Config &new_config, uint32_t level)


opencv_apps
Author(s): Kei Okada
autogenerated on Sat Aug 22 2020 03:35:08