48 #include <opencv2/highgui/highgui.hpp>
49 #include <opencv2/imgproc/imgproc.hpp>
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"
61 bool compareContourAreas(
const std::vector<cv::Point>& contour1,
const std::vector<cv::Point>& contour2)
63 double i = fabs(contourArea(cv::Mat(contour1)));
64 double j = fabs(contourArea(cv::Mat(contour2)));
77 typedef opencv_apps::ContourMomentsConfig
Config;
97 const std::string&
frameWithDefault(
const std::string& frame,
const std::string& image_frame)
106 doWork(msg, cam_info->header.frame_id);
119 void doWork(
const sensor_msgs::ImageConstPtr& msg,
const std::string& input_frame_from_msg)
128 opencv_apps::MomentArrayStamped moments_msg;
129 moments_msg.header = msg->header;
134 if (frame.channels() > 1)
136 cv::cvtColor(frame, src_gray, cv::COLOR_BGR2GRAY);
142 cv::blur(src_gray, src_gray, cv::Size(3, 3));
150 cv::Mat canny_output;
151 std::vector<std::vector<cv::Point> > contours;
152 std::vector<cv::Vec4i> hierarchy;
158 cv::findContours(canny_output, contours, hierarchy, CV_RETR_TREE, CV_CHAIN_APPROX_SIMPLE, cv::Point(0, 0));
166 drawing = cv::Mat::zeros(canny_output.size(), CV_8UC3);
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++)
180 for (
size_t i = 0; i < contours.size(); i++)
182 mu[i] = moments(contours[i],
false);
186 for (
size_t i = 0; i < contours.size(); i++)
188 mc[i] = cv::Point2f(
static_cast<float>(mu[i].m10 / mu[i].m00),
static_cast<float>(mu[i].m01 / mu[i].m00));
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);
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,
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);
238 int c = cv::waitKey(1);
249 catch (cv::Exception& e)
251 NODELET_ERROR(
"Image processing error: %s %s %s %i", e.err.c_str(), e.func.c_str(), e.file.c_str(), e.line);
296 msg_pub_ = advertise<opencv_apps::MomentArrayStamped>(*
pnh_,
"moments", 1);
310 ROS_WARN(
"DeprecationWarning: Nodelet contour_moments/contour_moments is deprecated, "
311 "and renamed to opencv_apps/contour_moments.");
317 #ifdef USE_PLUGINLIB_CLASS_LIST_MACROS_H