contour_moments_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/tutorial_code/ShapeDescriptors/moments_demo.cpp
42 #include <ros/ros.h>
43 #include "opencv_apps/nodelet.h"
46 #include <cv_bridge/cv_bridge.h>
47 
48 #include <opencv2/highgui/highgui.hpp>
49 #include <opencv2/imgproc/imgproc.hpp>
50 
51 #include <dynamic_reconfigure/server.h>
52 #include "opencv_apps/ContourMomentsConfig.h"
53 #include "opencv_apps/Moment.h"
54 #include "opencv_apps/MomentArray.h"
55 #include "opencv_apps/MomentArrayStamped.h"
56 
57 namespace opencv_apps
58 {
59 // https://stackoverflow.com/questions/13495207/opencv-c-sorting-contours-by-their-contourarea
60 // comparison function object
61 bool compareContourAreas(const std::vector<cv::Point>& contour1, const std::vector<cv::Point>& contour2)
62 {
63  double i = fabs(contourArea(cv::Mat(contour1)));
64  double j = fabs(contourArea(cv::Mat(contour2)));
65  return (i > j);
66 }
67 
68 class ContourMomentsNodelet : public opencv_apps::Nodelet
69 {
74 
76 
77  typedef opencv_apps::ContourMomentsConfig Config;
78  typedef dynamic_reconfigure::Server<Config> ReconfigureServer;
81 
82  int queue_size_;
83  bool debug_view_;
85 
86  int low_threshold_;
87 
88  std::string window_name_;
89  static bool need_config_update_;
90 
91  void reconfigureCallback(Config& new_config, uint32_t level)
92  {
93  config_ = new_config;
94  low_threshold_ = config_.canny_low_threshold;
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  {
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, msg->encoding)->image;
126 
127  // Messages
128  opencv_apps::MomentArrayStamped moments_msg;
129  moments_msg.header = msg->header;
130 
131  // Do the work
132  cv::Mat src_gray;
134  if (frame.channels() > 1)
135  {
136  cv::cvtColor(frame, src_gray, cv::COLOR_BGR2GRAY);
137  }
138  else
139  {
140  src_gray = frame;
141  }
142  cv::blur(src_gray, src_gray, cv::Size(3, 3));
143 
145  if (debug_view_)
146  {
147  cv::namedWindow(window_name_, cv::WINDOW_AUTOSIZE);
148  }
149 
150  cv::Mat canny_output;
151  std::vector<std::vector<cv::Point> > contours;
152  std::vector<cv::Vec4i> hierarchy;
153  cv::RNG rng(12345);
154 
156  cv::Canny(src_gray, canny_output, low_threshold_, low_threshold_ * 2, 3);
158  cv::findContours(canny_output, contours, hierarchy, CV_RETR_TREE, CV_CHAIN_APPROX_SIMPLE, cv::Point(0, 0));
159 
161  cv::Mat drawing;
163  bool publish_drawing = (img_pub_.getNumSubscribers() > 0);
164  if (publish_drawing)
165  {
166  drawing = cv::Mat::zeros(canny_output.size(), CV_8UC3);
167  }
168 
170  NODELET_INFO("\t Info: Area and Contour Length");
171 
172  // https://stackoverflow.com/questions/13495207/opencv-c-sorting-contours-by-their-contourarea
173  std::sort(contours.begin(), contours.end(), compareContourAreas);
174 
175  std::vector<cv::Moments> mu(contours.size());
176  std::vector<cv::Point2f> mc(contours.size());
177  for (size_t i = 0; i < contours.size(); i++)
178  {
180  for (size_t i = 0; i < contours.size(); i++)
181  {
182  mu[i] = moments(contours[i], false);
183  }
184 
186  for (size_t i = 0; i < contours.size(); i++)
187  {
188  mc[i] = cv::Point2f(static_cast<float>(mu[i].m10 / mu[i].m00), static_cast<float>(mu[i].m01 / mu[i].m00));
189  }
190 
191  if (publish_drawing)
192  {
193  cv::Scalar color = cv::Scalar(rng.uniform(0, 255), rng.uniform(0, 255), rng.uniform(0, 255));
194  cv::drawContours(drawing, contours, (int)i, color, 2, 8, hierarchy, 0, cv::Point());
195  cv::circle(drawing, mc[i], 4, color, -1, 8, 0);
196  }
197  NODELET_INFO(" * Contour[%d] - Area (M_00) = %.2f - Area OpenCV: %.2f - Length: %.2f - Center (%.2f, %.2f)",
198  (int)i, mu[i].m00, cv::contourArea(contours[i]), cv::arcLength(contours[i], true), mc[i].x,
199  mc[i].y);
200 
201  opencv_apps::Moment moment_msg;
202  moment_msg.m00 = mu[i].m00;
203  moment_msg.m10 = mu[i].m10;
204  moment_msg.m01 = mu[i].m01;
205  moment_msg.m20 = mu[i].m20;
206  moment_msg.m11 = mu[i].m11;
207  moment_msg.m02 = mu[i].m02;
208  moment_msg.m30 = mu[i].m30;
209  moment_msg.m21 = mu[i].m21;
210  moment_msg.m12 = mu[i].m12;
211  moment_msg.m03 = mu[i].m03;
212  moment_msg.mu20 = mu[i].mu20;
213  moment_msg.mu11 = mu[i].mu11;
214  moment_msg.mu02 = mu[i].mu02;
215  moment_msg.mu30 = mu[i].mu30;
216  moment_msg.mu21 = mu[i].mu21;
217  moment_msg.mu12 = mu[i].mu12;
218  moment_msg.mu03 = mu[i].mu03;
219  moment_msg.nu20 = mu[i].nu20;
220  moment_msg.nu11 = mu[i].nu11;
221  moment_msg.nu02 = mu[i].nu02;
222  moment_msg.nu30 = mu[i].nu30;
223  moment_msg.nu21 = mu[i].nu21;
224  moment_msg.nu12 = mu[i].nu12;
225  moment_msg.nu03 = mu[i].nu03;
226  opencv_apps::Point2D center_msg;
227  center_msg.x = mc[i].x;
228  center_msg.y = mc[i].y;
229  moment_msg.center = center_msg;
230  moment_msg.area = cv::contourArea(contours[i]);
231  moment_msg.length = cv::arcLength(contours[i], true);
232  moments_msg.moments.push_back(moment_msg);
233  }
234 
235  if (debug_view_)
236  {
237  cv::imshow(window_name_, drawing);
238  int c = cv::waitKey(1);
239  }
240 
241  // Publish the image.
242  if (publish_drawing)
243  {
244  sensor_msgs::Image::Ptr out_img = cv_bridge::CvImage(msg->header, "bgr8", drawing).toImageMsg();
245  img_pub_.publish(out_img);
246  }
247  msg_pub_.publish(moments_msg);
248  }
249  catch (cv::Exception& e)
250  {
251  NODELET_ERROR("Image processing error: %s %s %s %i", e.err.c_str(), e.func.c_str(), e.file.c_str(), e.line);
252  }
253 
254  prev_stamp_ = msg->header.stamp;
255  }
256 
257  void subscribe() // NOLINT(modernize-use-override)
258  {
259  NODELET_DEBUG("Subscribing to image topic.");
260  if (config_.use_camera_info)
261  cam_sub_ = it_->subscribeCamera("image", queue_size_, &ContourMomentsNodelet::imageCallbackWithInfo, this);
262  else
263  img_sub_ = it_->subscribe("image", queue_size_, &ContourMomentsNodelet::imageCallback, this);
264  }
265 
266  void unsubscribe() // NOLINT(modernize-use-override)
267  {
268  NODELET_DEBUG("Unsubscribing from image topic.");
269  img_sub_.shutdown();
270  cam_sub_.shutdown();
271  }
272 
273 public:
274  virtual void onInit() // NOLINT(modernize-use-override)
275  {
276  Nodelet::onInit();
278 
279  pnh_->param("queue_size", queue_size_, 3);
280  pnh_->param("debug_view", debug_view_, false);
281  if (debug_view_)
282  {
283  always_subscribe_ = true;
284  }
285  prev_stamp_ = ros::Time(0, 0);
286 
287  window_name_ = "Contours";
288  low_threshold_ = 100; // only for canny
289 
290  reconfigure_server_ = boost::make_shared<dynamic_reconfigure::Server<Config> >(*pnh_);
291  dynamic_reconfigure::Server<Config>::CallbackType f = boost::bind(&ContourMomentsNodelet::reconfigureCallback, this,
293  reconfigure_server_->setCallback(f);
294 
295  img_pub_ = advertiseImage(*pnh_, "image", 1);
296  msg_pub_ = advertise<opencv_apps::MomentArrayStamped>(*pnh_, "moments", 1);
298  }
299 };
301 } // namespace opencv_apps
302 
304 {
306 {
307 public:
308  virtual void onInit() // NOLINT(modernize-use-override)
309  {
310  ROS_WARN("DeprecationWarning: Nodelet contour_moments/contour_moments is deprecated, "
311  "and renamed to opencv_apps/contour_moments.");
313  }
314 };
315 } // namespace contour_moments
316 
317 #ifdef USE_PLUGINLIB_CLASS_LIST_MACROS_H
319 #else
321 #endif
opencv_apps::ContourMomentsNodelet::need_config_update_
static bool need_config_update_
Definition: contour_moments_nodelet.cpp:121
nodelet.h
contour_moments::ContourMomentsNodelet
Definition: contour_moments_nodelet.cpp:305
opencv_apps::ContourMomentsNodelet::reconfigure_server_
boost::shared_ptr< ReconfigureServer > reconfigure_server_
Definition: contour_moments_nodelet.cpp:112
NODELET_ERROR
#define NODELET_ERROR(...)
opencv_apps::Nodelet::onInitPostProcess
virtual void onInitPostProcess()
Post processing of initialization of nodelet. You need to call this method in order to use always_sub...
Definition: nodelet.cpp:77
ros::Publisher
image_encodings.h
image_transport::ImageTransport
boost::shared_ptr< image_transport::ImageTransport >
opencv_apps::ContourMomentsNodelet::config_
Config config_
Definition: contour_moments_nodelet.cpp:111
cv_bridge::CvImage::toImageMsg
sensor_msgs::ImagePtr toImageMsg() const
contour_moments
Definition: contour_moments_nodelet.cpp:303
ros.h
boost::placeholders::_1
boost::arg< 1 > _1
Definition: nodelet.cpp:44
opencv_apps::Nodelet
Nodelet to automatically subscribe/unsubscribe topics according to subscription of advertised topics.
Definition: nodelet.h:90
image_transport::Publisher::getNumSubscribers
uint32_t getNumSubscribers() const
opencv_apps::ContourMomentsNodelet::Config
opencv_apps::ContourMomentsConfig Config
Definition: contour_moments_nodelet.cpp:109
opencv_apps::ContourMomentsNodelet::debug_view_
bool debug_view_
Definition: contour_moments_nodelet.cpp:115
opencv_apps::ContourMomentsNodelet::msg_pub_
ros::Publisher msg_pub_
Definition: contour_moments_nodelet.cpp:105
opencv_apps::ContourMomentsNodelet::cam_sub_
image_transport::CameraSubscriber cam_sub_
Definition: contour_moments_nodelet.cpp:104
ros::Publisher::publish
void publish(const boost::shared_ptr< M > &message) const
PLUGINLIB_EXPORT_CLASS
PLUGINLIB_EXPORT_CLASS(opencv_apps::ContourMomentsNodelet, nodelet::Nodelet)
f
f
image_transport::Subscriber
opencv_apps::compareContourAreas
bool compareContourAreas(const std::vector< cv::Point > &contour1, const std::vector< cv::Point > &contour2)
Definition: contour_moments_nodelet.cpp:93
opencv_apps::Nodelet::advertiseImage
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:201
class_list_macros.h
opencv_apps::ContourMomentsNodelet::prev_stamp_
ros::Time prev_stamp_
Definition: contour_moments_nodelet.cpp:116
opencv_apps::ContourMomentsNodelet::frameWithDefault
const std::string & frameWithDefault(const std::string &frame, const std::string &image_frame)
Definition: contour_moments_nodelet.cpp:129
opencv_apps::ContourMomentsNodelet::imageCallback
void imageCallback(const sensor_msgs::ImageConstPtr &msg)
Definition: contour_moments_nodelet.cpp:141
image_transport::CameraSubscriber
opencv_apps::ContourMomentsNodelet::img_pub_
image_transport::Publisher img_pub_
Definition: contour_moments_nodelet.cpp:102
image_transport::CameraSubscriber::shutdown
void shutdown()
boost::placeholders::_2
boost::arg< 2 > _2
Definition: nodelet.cpp:45
opencv_apps::ContourMomentsNodelet::onInit
virtual void onInit()
Initialize nodehandles nh_ and pnh_. Subclass should call this method in its onInit method.
Definition: contour_moments_nodelet.cpp:306
opencv_apps::Nodelet::always_subscribe_
bool always_subscribe_
A flag to disable watching mechanism and always subscribe input topics. It can be specified via ~alwa...
Definition: nodelet.h:300
ROS_WARN
#define ROS_WARN(...)
opencv_apps::ContourMomentsNodelet::unsubscribe
void unsubscribe()
This method is called when publisher is unsubscribed by other nodes. Shut down subscribers in this me...
Definition: contour_moments_nodelet.cpp:298
opencv_apps::ContourMomentsNodelet
Definition: contour_moments_nodelet.cpp:100
image_transport::Publisher::publish
void publish(const sensor_msgs::Image &message) const
opencv_apps
Demo code to calculate moments.
Definition: nodelet.h:68
opencv_apps::ContourMomentsNodelet::img_sub_
image_transport::Subscriber img_sub_
Definition: contour_moments_nodelet.cpp:103
opencv_apps::ContourMomentsNodelet::low_threshold_
int low_threshold_
Definition: contour_moments_nodelet.cpp:118
image_transport.h
opencv_apps::ContourMomentsNodelet::imageCallbackWithInfo
void imageCallbackWithInfo(const sensor_msgs::ImageConstPtr &msg, const sensor_msgs::CameraInfoConstPtr &cam_info)
Definition: contour_moments_nodelet.cpp:136
NODELET_INFO
#define NODELET_INFO(...)
nodelet::Nodelet
opencv_apps::ContourMomentsNodelet::it_
boost::shared_ptr< image_transport::ImageTransport > it_
Definition: contour_moments_nodelet.cpp:107
ros::Time
image_transport::Publisher
opencv_apps::ContourMomentsNodelet::ReconfigureServer
dynamic_reconfigure::Server< Config > ReconfigureServer
Definition: contour_moments_nodelet.cpp:110
cv_bridge.h
cv_bridge::CvImage
class_list_macros.hpp
opencv_apps::ContourMomentsNodelet::reconfigureCallback
void reconfigureCallback(Config &new_config, uint32_t level)
Definition: contour_moments_nodelet.cpp:123
opencv_apps::ContourMomentsNodelet::doWork
void doWork(const sensor_msgs::ImageConstPtr &msg, const std::string &input_frame_from_msg)
Definition: contour_moments_nodelet.cpp:151
cv_bridge::toCvShare
CvImageConstPtr toCvShare(const sensor_msgs::Image &source, const boost::shared_ptr< void const > &tracked_object, const std::string &encoding=std::string())
opencv_apps::ContourMomentsNodelet::subscribe
void subscribe()
This method is called when publisher is subscribed by other nodes. Set up subscribers in this method.
Definition: contour_moments_nodelet.cpp:289
opencv_apps::ContourMomentsNodelet::trackbarCallback
static void trackbarCallback(int, void *)
Definition: contour_moments_nodelet.cpp:146
opencv_apps::Nodelet::nh_
boost::shared_ptr< ros::NodeHandle > nh_
Shared pointer to nodehandle.
Definition: nodelet.h:272
contour_moments::ContourMomentsNodelet::onInit
virtual void onInit()
Initialize nodehandles nh_ and pnh_. Subclass should call this method in its onInit method.
Definition: contour_moments_nodelet.cpp:308
opencv_apps::ContourMomentsNodelet::window_name_
std::string window_name_
Definition: contour_moments_nodelet.cpp:120
opencv_apps::ContourMomentsNodelet::queue_size_
int queue_size_
Definition: contour_moments_nodelet.cpp:114
opencv_apps::Nodelet::onInit
virtual void onInit()
Initialize nodehandles nh_ and pnh_. Subclass should call this method in its onInit method.
Definition: nodelet.cpp:60
opencv_apps::Nodelet::pnh_
boost::shared_ptr< ros::NodeHandle > pnh_
Shared pointer to private nodehandle.
Definition: nodelet.h:277
NODELET_DEBUG
#define NODELET_DEBUG(...)
image_transport::Subscriber::shutdown
void shutdown()


opencv_apps
Author(s): Kei Okada
autogenerated on Fri May 23 2025 02:49:49