59 #include <opencv2/highgui/highgui.hpp> 60 #include <opencv2/imgproc/imgproc.hpp> 62 #include <dynamic_reconfigure/server.h> 63 #include "opencv_apps/EdgeDetectionConfig.h" 76 typedef opencv_apps::EdgeDetectionConfig
Config;
100 canny_threshold1_ = config_.canny_threshold1;
101 canny_threshold2_ = config_.canny_threshold2;
102 apertureSize_ = 2 * ((config_.apertureSize / 2)) + 1;
103 L2gradient_ = config_.L2gradient;
105 apply_blur_pre_ = config_.apply_blur_pre;
106 apply_blur_post_ = config_.apply_blur_post;
107 postBlurSize_ = 2 * ((config_.postBlurSize) / 2) + 1;
108 postBlurSigma_ = config_.postBlurSigma;
111 const std::string&
frameWithDefault(
const std::string& frame,
const std::string& image_frame)
120 doWork(msg, cam_info->header.frame_id);
125 doWork(msg, msg->header.frame_id);
130 need_config_update_ =
true;
133 void doWork(
const sensor_msgs::ImageConstPtr& msg,
const std::string& input_frame_from_msg)
143 cv::GaussianBlur(frame, frame, cv::Size(3, 3), 0, 0, cv::BORDER_DEFAULT);
146 if (frame.channels() > 1)
148 cv::cvtColor(frame, src_gray, cv::COLOR_RGB2GRAY);
158 cv::namedWindow(window_name_, cv::WINDOW_AUTOSIZE);
161 std::string new_window_name;
163 switch (config_.edge_type)
165 case opencv_apps::EdgeDetection_Sobel:
168 cv::Mat grad_x, grad_y;
169 cv::Mat abs_grad_x, abs_grad_y;
177 cv::Sobel(src_gray, grad_x, ddepth, 1, 0, 3, scale, delta, cv::BORDER_DEFAULT);
178 cv::convertScaleAbs(grad_x, abs_grad_x);
182 cv::Sobel(src_gray, grad_y, ddepth, 0, 1, 3, scale, delta, cv::BORDER_DEFAULT);
183 cv::convertScaleAbs(grad_y, abs_grad_y);
186 cv::addWeighted(abs_grad_x, 0.5, abs_grad_y, 0.5, 0, grad);
188 new_window_name =
"Sobel Edge Detection Demo";
191 case opencv_apps::EdgeDetection_Laplace:
200 cv::Laplacian(src_gray, dst, ddepth, kernel_size, scale, delta, cv::BORDER_DEFAULT);
201 convertScaleAbs(dst, grad);
203 new_window_name =
"Laplace Edge Detection Demo";
206 case opencv_apps::EdgeDetection_Canny:
210 int const max_canny_threshold1 = 500;
211 int const max_canny_threshold2 = 500;
212 cv::Mat detected_edges;
217 cv::blur(src_gray, src_gray, cv::Size(apertureSize_, apertureSize_));
221 cv::Canny(src_gray, grad, canny_threshold1_, canny_threshold2_, kernel_size, L2gradient_);
222 if (apply_blur_post_)
224 cv::GaussianBlur(grad, grad, cv::Size(postBlurSize_, postBlurSize_), postBlurSigma_,
228 new_window_name =
"Canny Edge Detection Demo";
233 if (need_config_update_)
237 reconfigure_server_->updateConfig(config_);
238 need_config_update_ =
false;
240 if (window_name_ == new_window_name)
242 cv::createTrackbar(
"Min CannyThreshold1:", window_name_, &canny_threshold1_, max_canny_threshold1,
244 cv::createTrackbar(
"Min CannyThreshold2:", window_name_, &canny_threshold2_, max_canny_threshold2,
254 if (window_name_ != new_window_name)
256 cv::destroyWindow(window_name_);
257 window_name_ = new_window_name;
259 cv::imshow(window_name_, grad);
260 int c = cv::waitKey(1);
264 sensor_msgs::Image::Ptr out_img =
268 catch (cv::Exception& e)
270 NODELET_ERROR(
"Image processing error: %s %s %s %i", e.err.c_str(), e.func.c_str(), e.file.c_str(), e.line);
273 prev_stamp_ = msg->header.stamp;
279 if (config_.use_camera_info)
298 pnh_->param(
"queue_size", queue_size_, 3);
299 pnh_->param(
"debug_view", debug_view_,
false);
307 window_name_ =
"Edge Detection Demo";
308 canny_threshold1_ = 100;
309 canny_threshold2_ = 200;
311 reconfigure_server_ = boost::make_shared<dynamic_reconfigure::Server<Config> >(*pnh_);
312 dynamic_reconfigure::Server<Config>::CallbackType
f =
314 reconfigure_server_->setCallback(f);
332 ROS_WARN(
"DeprecationWarning: Nodelet edge_detection/edge_detection is deprecated, " 333 "and renamed to opencv_apps/edge_detection.");
CvImageConstPtr toCvShare(const sensor_msgs::ImageConstPtr &source, const std::string &encoding=std::string())
opencv_apps::EdgeDetectionConfig Config
void unsubscribe()
This method is called when publisher is unsubscribed by other nodes. Shut down subscribers in this me...
#define NODELET_ERROR(...)
void reconfigureCallback(Config &new_config, uint32_t level)
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)
Nodelet to automatically subscribe/unsubscribe topics according to subscription of advertised topics...
boost::shared_ptr< image_transport::ImageTransport > it_
Demo code to calculate moments.
dynamic_reconfigure::Server< Config > ReconfigureServer
image_transport::CameraSubscriber cam_sub_
void imageCallbackWithInfo(const sensor_msgs::ImageConstPtr &msg, const sensor_msgs::CameraInfoConstPtr &cam_info)
boost::shared_ptr< ros::NodeHandle > pnh_
Shared pointer to private nodehandle.
virtual void onInit()
Initialize nodehandles nh_ and pnh_. Subclass should call this method in its onInit method...
PLUGINLIB_EXPORT_CLASS(opencv_apps::EdgeDetectionNodelet, nodelet::Nodelet)
image_transport::Publisher img_pub_
bool always_subscribe_
A flag to disable watching mechanism and always subscribe input topics. It can be specified via ~alwa...
boost::shared_ptr< ReconfigureServer > reconfigure_server_
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
static void trackbarCallback(int, void *)
boost::shared_ptr< ros::NodeHandle > nh_
Shared pointer to nodehandle.
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...
const std::string & frameWithDefault(const std::string &frame, const std::string &image_frame)
image_transport::Subscriber img_sub_
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(...)
sensor_msgs::ImagePtr toImageMsg() const
static bool need_config_update_