49 #include <opencv2/highgui/highgui.hpp> 50 #include <opencv2/imgproc/imgproc.hpp> 52 #include <dynamic_reconfigure/server.h> 53 #include "opencv_apps/GeneralContoursConfig.h" 54 #include "opencv_apps/RotatedRect.h" 55 #include "opencv_apps/RotatedRectArray.h" 56 #include "opencv_apps/RotatedRectArrayStamped.h" 69 typedef opencv_apps::GeneralContoursConfig
Config;
86 threshold_ = config_.threshold;
89 const std::string&
frameWithDefault(
const std::string& frame,
const std::string& image_frame)
96 void imageCallbackWithInfo(
const sensor_msgs::ImageConstPtr& msg,
const sensor_msgs::CameraInfoConstPtr& cam_info)
98 doWork(msg, cam_info->header.frame_id);
103 doWork(msg, msg->header.frame_id);
108 need_config_update_ =
true;
111 void doWork(
const sensor_msgs::ImageConstPtr& msg,
const std::string& input_frame_from_msg)
120 opencv_apps::RotatedRectArrayStamped rects_msg, ellipses_msg;
121 rects_msg.header = msg->header;
122 ellipses_msg.header = msg->header;
128 if (frame.channels() > 1)
130 cv::cvtColor(frame, src_gray, cv::COLOR_RGB2GRAY);
136 cv::blur(src_gray, src_gray, cv::Size(3, 3));
141 cv::namedWindow(window_name_, cv::WINDOW_AUTOSIZE);
144 cv::Mat threshold_output;
145 int max_thresh = 255;
146 std::vector<std::vector<cv::Point> > contours;
147 std::vector<cv::Vec4i> hierarchy;
151 cv::threshold(src_gray, threshold_output, threshold_, 255, cv::THRESH_BINARY);
154 cv::findContours(threshold_output, contours, hierarchy, CV_RETR_TREE, CV_CHAIN_APPROX_SIMPLE, cv::Point(0, 0));
157 std::vector<cv::RotatedRect> min_rect(contours.size());
158 std::vector<cv::RotatedRect> min_ellipse(contours.size());
160 for (
size_t i = 0; i < contours.size(); i++)
162 min_rect[i] = cv::minAreaRect(cv::Mat(contours[i]));
163 if (contours[i].size() > 5)
165 min_ellipse[i] = cv::fitEllipse(cv::Mat(contours[i]));
170 cv::Mat drawing = cv::Mat::zeros(threshold_output.size(), CV_8UC3);
171 for (
size_t i = 0; i < contours.size(); i++)
173 cv::Scalar color = cv::Scalar(rng.uniform(0, 255), rng.uniform(0, 255), rng.uniform(0, 255));
175 cv::drawContours(drawing, contours, (
int)i, color, 1, 8, std::vector<cv::Vec4i>(), 0, cv::Point());
177 cv::ellipse(drawing, min_ellipse[i], color, 2, 8);
179 cv::Point2f rect_points[4];
180 min_rect[i].points(rect_points);
181 for (
int j = 0; j < 4; j++)
182 cv::line(drawing, rect_points[j], rect_points[(j + 1) % 4], color, 1, 8);
184 opencv_apps::RotatedRect rect_msg;
185 opencv_apps::Point2D rect_center;
186 opencv_apps::Size rect_size;
187 rect_center.x = min_rect[i].center.x;
188 rect_center.y = min_rect[i].center.y;
189 rect_size.width = min_rect[i].size.width;
190 rect_size.height = min_rect[i].size.height;
191 rect_msg.center = rect_center;
192 rect_msg.size = rect_size;
193 rect_msg.angle = min_rect[i].angle;
194 opencv_apps::RotatedRect ellipse_msg;
195 opencv_apps::Point2D ellipse_center;
196 opencv_apps::Size ellipse_size;
197 ellipse_center.x = min_ellipse[i].center.x;
198 ellipse_center.y = min_ellipse[i].center.y;
199 ellipse_size.width = min_ellipse[i].size.width;
200 ellipse_size.height = min_ellipse[i].size.height;
201 ellipse_msg.center = ellipse_center;
202 ellipse_msg.size = ellipse_size;
203 ellipse_msg.angle = min_ellipse[i].angle;
205 rects_msg.rects.push_back(rect_msg);
206 ellipses_msg.rects.push_back(ellipse_msg);
212 if (need_config_update_)
215 reconfigure_server_->updateConfig(config_);
216 need_config_update_ =
false;
218 cv::createTrackbar(
"Threshold:", window_name_, &threshold_, max_thresh,
trackbarCallback);
220 cv::imshow(window_name_, drawing);
221 int c = cv::waitKey(1);
225 sensor_msgs::Image::Ptr out_img =
229 ellipses_pub_.
publish(ellipses_msg);
231 catch (cv::Exception& e)
233 NODELET_ERROR(
"Image processing error: %s %s %s %i", e.err.c_str(), e.func.c_str(), e.file.c_str(), e.line);
236 prev_stamp_ = msg->header.stamp;
242 if (config_.use_camera_info)
261 pnh_->param(
"queue_size", queue_size_, 3);
262 pnh_->param(
"debug_view", debug_view_,
false);
269 window_name_ =
"Contours";
272 reconfigure_server_ = boost::make_shared<dynamic_reconfigure::Server<Config> >(*pnh_);
273 dynamic_reconfigure::Server<Config>::CallbackType
f =
275 reconfigure_server_->setCallback(f);
278 rects_pub_ = advertise<opencv_apps::RotatedRectArrayStamped>(*
pnh_,
"rectangles", 1);
279 ellipses_pub_ = advertise<opencv_apps::RotatedRectArrayStamped>(*
pnh_,
"ellipses", 1);
294 ROS_WARN(
"DeprecationWarning: Nodelet general_contours/general_contours is deprecated, " 295 "and renamed to opencv_apps/general_contours.");
image_transport::Subscriber img_sub_
CvImageConstPtr toCvShare(const sensor_msgs::ImageConstPtr &source, const std::string &encoding=std::string())
static bool need_config_update_
image_transport::Publisher img_pub_
boost::shared_ptr< ReconfigureServer > reconfigure_server_
void reconfigureCallback(Config &new_config, uint32_t level)
#define NODELET_ERROR(...)
void publish(const boost::shared_ptr< M > &message) const
virtual void onInit()
Initialize nodehandles nh_ and pnh_. Subclass should call this method in its onInit method...
virtual void onInit()
Initialize nodehandles nh_ and pnh_. Subclass should call this method in its onInit method...
Nodelet to automatically subscribe/unsubscribe topics according to subscription of advertised topics...
void doWork(const sensor_msgs::ImageConstPtr &msg, const std::string &input_frame_from_msg)
Demo code to calculate moments.
void imageCallback(const sensor_msgs::ImageConstPtr &msg)
boost::shared_ptr< image_transport::ImageTransport > it_
void unsubscribe()
This method is called when publisher is unsubscribed by other nodes. Shut down subscribers in this me...
boost::shared_ptr< ros::NodeHandle > pnh_
Shared pointer to private nodehandle.
static void trackbarCallback(int, void *)
image_transport::CameraSubscriber cam_sub_
ros::Publisher ellipses_pub_
bool always_subscribe_
A flag to disable watching mechanism and always subscribe input topics. It can be specified via ~alwa...
virtual void onInitPostProcess()
Post processing of initialization of nodelet. You need to call this method in order to use always_sub...
virtual void onInit()
Initialize nodehandles nh_ and pnh_. Subclass should call this method in its onInit method...
void publish(const sensor_msgs::Image &message) const
boost::shared_ptr< ros::NodeHandle > nh_
Shared pointer to nodehandle.
PLUGINLIB_EXPORT_CLASS(opencv_apps::GeneralContoursNodelet, nodelet::Nodelet)
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...
const std::string & frameWithDefault(const std::string &frame, const std::string &image_frame)
void subscribe()
This method is called when publisher is subscribed by other nodes. Set up subscribers in this method...
void imageCallbackWithInfo(const sensor_msgs::ImageConstPtr &msg, const sensor_msgs::CameraInfoConstPtr &cam_info)
ros::Publisher rects_pub_
#define NODELET_DEBUG(...)
sensor_msgs::ImagePtr toImageMsg() const
dynamic_reconfigure::Server< Config > ReconfigureServer
opencv_apps::GeneralContoursConfig Config