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>
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"
73 typedef opencv_apps::SegmentObjectsConfig
Config;
85 #ifndef CV_VERSION_EPOCH
97 const std::string&
frameWithDefault(
const std::string& frame,
const std::string& image_frame)
104 void imageCallbackWithInfo(
const sensor_msgs::ImageConstPtr& msg,
const sensor_msgs::CameraInfoConstPtr& cam_info)
106 doWork(msg, cam_info->header.frame_id);
111 doWork(msg, msg->header.frame_id);
119 void doWork(
const sensor_msgs::ImageConstPtr& msg,
const std::string& input_frame_from_msg)
128 opencv_apps::ContourArrayStamped contours_msg;
129 contours_msg.header = msg->header;
132 cv::Mat bgmask, out_frame;
145 #ifndef CV_VERSION_EPOCH
153 std::vector<std::vector<cv::Point> > contours;
154 std::vector<cv::Vec4i> hierarchy;
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);
162 cv::findContours(temp, contours, hierarchy, CV_RETR_CCOMP, CV_CHAIN_APPROX_SIMPLE);
164 out_frame = cv::Mat::zeros(frame.size(), CV_8UC3);
166 if (contours.empty())
171 int idx = 0, largest_comp = 0;
174 for (; idx >= 0; idx = hierarchy[idx][0])
176 const std::vector<cv::Point>& c = contours[idx];
177 double area = fabs(cv::contourArea(cv::Mat(c)));
184 cv::Scalar color(0, 0, 255);
185 cv::drawContours(out_frame, contours, largest_comp, color, CV_FILLED, 8, hierarchy);
187 std_msgs::Float64 area_msg;
188 area_msg.data = max_area;
189 for (
const std::vector<cv::Point>& contour : contours)
191 opencv_apps::Contour contour_msg;
192 for (
const cv::Point& j : contour)
194 opencv_apps::Point2D point_msg;
197 contour_msg.points.push_back(point_msg);
199 contours_msg.contours.push_back(contour_msg);
206 int keycode = cv::waitKey(1);
217 sensor_msgs::Image::Ptr out_img =
223 catch (cv::Exception& e)
225 NODELET_ERROR(
"Image processing error: %s %s %s %i", e.err.c_str(), e.func.c_str(), e.file.c_str(), e.line);
231 bool updateBgModelCb(std_srvs::Empty::Request& request, std_srvs::Empty::Response& response)
271 #ifndef CV_VERSION_EPOCH
283 msg_pub_ = advertise<opencv_apps::ContourArrayStamped>(*
pnh_,
"contours", 1);
300 ROS_WARN(
"DeprecationWarning: Nodelet segment_objects/segment_objects is deprecated, "
301 "and renamed to opencv_apps/segment_objects.");
307 #ifdef USE_PLUGINLIB_CLASS_LIST_MACROS_H