
Public Member Functions | |
| virtual void | onInit () |
| Initialize nodehandles nh_ and pnh_. Subclass should call this method in its onInit method. | |
Private Types | |
| typedef edge_detection::EdgeDetectionConfig | Config |
| typedef dynamic_reconfigure::Server < Config > | ReconfigureServer |
Private Member Functions | |
| void | do_work (const sensor_msgs::ImageConstPtr &msg, const std::string input_frame_from_msg) |
| const std::string & | frameWithDefault (const std::string &frame, const std::string &image_frame) |
| void | imageCallback (const sensor_msgs::ImageConstPtr &msg) |
| void | imageCallbackWithInfo (const sensor_msgs::ImageConstPtr &msg, const sensor_msgs::CameraInfoConstPtr &cam_info) |
| 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 | unsubscribe () |
| This method is called when publisher is unsubscribed by other nodes. Shut down subscribers in this method. | |
Static Private Member Functions | |
| static void | trackbarCallback (int, void *) |
Private Attributes | |
| int | apertureSize_ |
| bool | apply_blur_post_ |
| bool | apply_blur_pre_ |
| image_transport::CameraSubscriber | cam_sub_ |
| int | canny_threshold1_ |
| int | canny_threshold2_ |
| Config | config_ |
| bool | debug_view_ |
| image_transport::Publisher | img_pub_ |
| image_transport::Subscriber | img_sub_ |
| boost::shared_ptr < image_transport::ImageTransport > | it_ |
| bool | L2gradient_ |
| ros::Publisher | msg_pub_ |
| double | postBlurSigma_ |
| int | postBlurSize_ |
| ros::Time | prev_stamp_ |
| boost::shared_ptr < ReconfigureServer > | reconfigure_server_ |
| std::string | window_name_ |
Static Private Attributes | |
| static bool | need_config_update_ = false |
Definition at line 66 of file edge_detection_nodelet.cpp.
typedef edge_detection::EdgeDetectionConfig edge_detection::EdgeDetectionNodelet::Config [private] |
Definition at line 75 of file edge_detection_nodelet.cpp.
typedef dynamic_reconfigure::Server<Config> edge_detection::EdgeDetectionNodelet::ReconfigureServer [private] |
Definition at line 76 of file edge_detection_nodelet.cpp.
| void edge_detection::EdgeDetectionNodelet::do_work | ( | const sensor_msgs::ImageConstPtr & | msg, |
| const std::string | input_frame_from_msg | ||
| ) | [inline, private] |
Convert it to gray
Create window
Generate grad_x and grad_y
Gradient X
Gradient Y
Total Gradient (approximate)
Apply Laplace function
Reduce noise with a kernel 3x3
Canny detector
Create a Trackbar for user to enter threshold
Definition at line 131 of file edge_detection_nodelet.cpp.
| const std::string& edge_detection::EdgeDetectionNodelet::frameWithDefault | ( | const std::string & | frame, |
| const std::string & | image_frame | ||
| ) | [inline, private] |
Definition at line 109 of file edge_detection_nodelet.cpp.
| void edge_detection::EdgeDetectionNodelet::imageCallback | ( | const sensor_msgs::ImageConstPtr & | msg | ) | [inline, private] |
Definition at line 121 of file edge_detection_nodelet.cpp.
| void edge_detection::EdgeDetectionNodelet::imageCallbackWithInfo | ( | const sensor_msgs::ImageConstPtr & | msg, |
| const sensor_msgs::CameraInfoConstPtr & | cam_info | ||
| ) | [inline, private] |
Definition at line 116 of file edge_detection_nodelet.cpp.
| virtual void edge_detection::EdgeDetectionNodelet::onInit | ( | ) | [inline, virtual] |
Initialize nodehandles nh_ and pnh_. Subclass should call this method in its onInit method.
Reimplemented from opencv_apps::Nodelet.
Definition at line 277 of file edge_detection_nodelet.cpp.
| void edge_detection::EdgeDetectionNodelet::reconfigureCallback | ( | Config & | new_config, |
| uint32_t | level | ||
| ) | [inline, private] |
Definition at line 95 of file edge_detection_nodelet.cpp.
| void edge_detection::EdgeDetectionNodelet::subscribe | ( | ) | [inline, private, virtual] |
This method is called when publisher is subscribed by other nodes. Set up subscribers in this method.
Implements opencv_apps::Nodelet.
Definition at line 260 of file edge_detection_nodelet.cpp.
| static void edge_detection::EdgeDetectionNodelet::trackbarCallback | ( | int | , |
| void * | |||
| ) | [inline, static, private] |
Definition at line 126 of file edge_detection_nodelet.cpp.
| void edge_detection::EdgeDetectionNodelet::unsubscribe | ( | ) | [inline, private, virtual] |
This method is called when publisher is unsubscribed by other nodes. Shut down subscribers in this method.
Implements opencv_apps::Nodelet.
Definition at line 269 of file edge_detection_nodelet.cpp.
int edge_detection::EdgeDetectionNodelet::apertureSize_ [private] |
Definition at line 85 of file edge_detection_nodelet.cpp.
bool edge_detection::EdgeDetectionNodelet::apply_blur_post_ [private] |
Definition at line 88 of file edge_detection_nodelet.cpp.
bool edge_detection::EdgeDetectionNodelet::apply_blur_pre_ [private] |
Definition at line 87 of file edge_detection_nodelet.cpp.
Definition at line 70 of file edge_detection_nodelet.cpp.
int edge_detection::EdgeDetectionNodelet::canny_threshold1_ [private] |
Definition at line 83 of file edge_detection_nodelet.cpp.
int edge_detection::EdgeDetectionNodelet::canny_threshold2_ [private] |
Definition at line 84 of file edge_detection_nodelet.cpp.
Definition at line 77 of file edge_detection_nodelet.cpp.
bool edge_detection::EdgeDetectionNodelet::debug_view_ [private] |
Definition at line 80 of file edge_detection_nodelet.cpp.
Definition at line 68 of file edge_detection_nodelet.cpp.
Definition at line 69 of file edge_detection_nodelet.cpp.
boost::shared_ptr<image_transport::ImageTransport> edge_detection::EdgeDetectionNodelet::it_ [private] |
Definition at line 73 of file edge_detection_nodelet.cpp.
bool edge_detection::EdgeDetectionNodelet::L2gradient_ [private] |
Definition at line 86 of file edge_detection_nodelet.cpp.
Definition at line 71 of file edge_detection_nodelet.cpp.
bool edge_detection::EdgeDetectionNodelet::need_config_update_ = false [static, private] |
Definition at line 93 of file edge_detection_nodelet.cpp.
double edge_detection::EdgeDetectionNodelet::postBlurSigma_ [private] |
Definition at line 90 of file edge_detection_nodelet.cpp.
int edge_detection::EdgeDetectionNodelet::postBlurSize_ [private] |
Definition at line 89 of file edge_detection_nodelet.cpp.
Definition at line 81 of file edge_detection_nodelet.cpp.
boost::shared_ptr<ReconfigureServer> edge_detection::EdgeDetectionNodelet::reconfigure_server_ [private] |
Definition at line 78 of file edge_detection_nodelet.cpp.
std::string edge_detection::EdgeDetectionNodelet::window_name_ [private] |
Definition at line 92 of file edge_detection_nodelet.cpp.