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;
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);
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);
161 std::string new_window_name;
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;
228 new_window_name =
"Canny Edge Detection Demo";
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);
312 dynamic_reconfigure::Server<Config>::CallbackType
f =
332 ROS_WARN(
"DeprecationWarning: Nodelet edge_detection/edge_detection is deprecated, "
333 "and renamed to opencv_apps/edge_detection.");
339 #ifdef USE_PLUGINLIB_CLASS_LIST_MACROS_H