49 #include <opencv2/highgui/highgui.hpp> 50 #include <opencv2/imgproc/imgproc.hpp> 52 #include <dynamic_reconfigure/server.h> 53 #include "opencv_apps/ConvexHullConfig.h" 54 #include "opencv_apps/Contour.h" 55 #include "opencv_apps/ContourArray.h" 56 #include "opencv_apps/ContourArrayStamped.h" 69 typedef opencv_apps::ConvexHullConfig
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::ContourArrayStamped contours_msg;
121 contours_msg.header = msg->header;
127 if (frame.channels() > 1)
129 cv::cvtColor(frame, src_gray, cv::COLOR_RGB2GRAY);
135 cv::blur(src_gray, src_gray, cv::Size(3, 3));
140 cv::namedWindow(window_name_, cv::WINDOW_AUTOSIZE);
143 cv::Mat threshold_output;
144 int max_thresh = 255;
145 std::vector<std::vector<cv::Point> > contours;
146 std::vector<cv::Vec4i> hierarchy;
150 cv::threshold(src_gray, threshold_output, threshold_, 255, cv::THRESH_BINARY);
153 cv::findContours(threshold_output, contours, hierarchy, CV_RETR_TREE, CV_CHAIN_APPROX_SIMPLE, cv::Point(0, 0));
156 std::vector<std::vector<cv::Point> > hull(contours.size());
157 for (
size_t i = 0; i < contours.size(); i++)
159 cv::convexHull(cv::Mat(contours[i]), hull[i],
false);
163 cv::Mat drawing = cv::Mat::zeros(threshold_output.size(), CV_8UC3);
164 for (
size_t i = 0; i < contours.size(); i++)
166 cv::Scalar color = cv::Scalar(rng.uniform(0, 255), rng.uniform(0, 255), rng.uniform(0, 255));
167 cv::drawContours(drawing, contours, (
int)i, color, 1, 8, std::vector<cv::Vec4i>(), 0, cv::Point());
168 cv::drawContours(drawing, hull, (
int)i, color, 4, 8, std::vector<cv::Vec4i>(), 0, cv::Point());
170 opencv_apps::Contour contour_msg;
171 for (
const cv::Point& j : hull[i])
173 opencv_apps::Point2D point_msg;
176 contour_msg.points.push_back(point_msg);
178 contours_msg.contours.push_back(contour_msg);
184 if (need_config_update_)
187 reconfigure_server_->updateConfig(config_);
188 need_config_update_ =
false;
190 cv::createTrackbar(
"Threshold:", window_name_, &threshold_, max_thresh,
trackbarCallback);
192 cv::imshow(window_name_, drawing);
193 int c = cv::waitKey(1);
197 sensor_msgs::Image::Ptr out_img =
200 msg_pub_.
publish(contours_msg);
202 catch (cv::Exception& e)
204 NODELET_ERROR(
"Image processing error: %s %s %s %i", e.err.c_str(), e.func.c_str(), e.file.c_str(), e.line);
207 prev_stamp_ = msg->header.stamp;
213 if (config_.use_camera_info)
232 pnh_->param(
"queue_size", queue_size_, 3);
233 pnh_->param(
"debug_view", debug_view_,
false);
240 window_name_ =
"Hull Demo";
243 reconfigure_server_ = boost::make_shared<dynamic_reconfigure::Server<Config> >(*pnh_);
244 dynamic_reconfigure::Server<Config>::CallbackType
f =
246 reconfigure_server_->setCallback(f);
249 msg_pub_ = advertise<opencv_apps::ContourArrayStamped>(*
pnh_,
"hulls", 1);
263 ROS_WARN(
"DeprecationWarning: Nodelet convex_hull/convex_hull is deprecated, " 264 "and renamed to opencv_apps/convex_hull.");
const std::string & frameWithDefault(const std::string &frame, const std::string &image_frame)
CvImageConstPtr toCvShare(const sensor_msgs::ImageConstPtr &source, const std::string &encoding=std::string())
void subscribe()
This method is called when publisher is subscribed by other nodes. Set up subscribers in this method...
void imageCallback(const sensor_msgs::ImageConstPtr &msg)
static void trackbarCallback(int, void *)
#define NODELET_ERROR(...)
opencv_apps::ConvexHullConfig Config
void publish(const boost::shared_ptr< M > &message) const
Nodelet to automatically subscribe/unsubscribe topics according to subscription of advertised topics...
void reconfigureCallback(Config &new_config, uint32_t level)
void imageCallbackWithInfo(const sensor_msgs::ImageConstPtr &msg, const sensor_msgs::CameraInfoConstPtr &cam_info)
Demo code to calculate moments.
image_transport::CameraSubscriber cam_sub_
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.
boost::shared_ptr< ReconfigureServer > reconfigure_server_
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
image_transport::Publisher img_pub_
static bool need_config_update_
boost::shared_ptr< ros::NodeHandle > nh_
Shared pointer to nodehandle.
dynamic_reconfigure::Server< Config > ReconfigureServer
virtual void onInit()
Initialize nodehandles nh_ and pnh_. Subclass should call this method in its onInit method...
void doWork(const sensor_msgs::ImageConstPtr &msg, const std::string &input_frame_from_msg)
virtual void onInit()
Initialize nodehandles nh_ and pnh_. Subclass should call this method in its onInit method...
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...
#define NODELET_DEBUG(...)
boost::shared_ptr< image_transport::ImageTransport > it_
PLUGINLIB_EXPORT_CLASS(opencv_apps::ConvexHullNodelet, nodelet::Nodelet)
sensor_msgs::ImagePtr toImageMsg() const
image_transport::Subscriber img_sub_