
| Public Member Functions | |
| virtual void | onInit () | 
| Initialize nodehandles nh_ and pnh_. Subclass should call this method in its onInit method. | |
| Private Types | |
| typedef opencv_apps::GeneralContoursConfig | Config | 
| typedef dynamic_reconfigure::Server < Config > | ReconfigureServer | 
| Private Member Functions | |
| void | doWork (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 | |
| image_transport::CameraSubscriber | cam_sub_ | 
| Config | config_ | 
| bool | debug_view_ | 
| ros::Publisher | ellipses_pub_ | 
| image_transport::Publisher | img_pub_ | 
| image_transport::Subscriber | img_sub_ | 
| boost::shared_ptr < image_transport::ImageTransport > | it_ | 
| ros::Time | prev_stamp_ | 
| int | queue_size_ | 
| boost::shared_ptr < ReconfigureServer > | reconfigure_server_ | 
| ros::Publisher | rects_pub_ | 
| int | threshold_ | 
| std::string | window_name_ | 
| Static Private Attributes | |
| static bool | need_config_update_ = false | 
Definition at line 60 of file general_contours_nodelet.cpp.
| typedef opencv_apps::GeneralContoursConfig opencv_apps::GeneralContoursNodelet::Config  [private] | 
Definition at line 69 of file general_contours_nodelet.cpp.
| typedef dynamic_reconfigure::Server<Config> opencv_apps::GeneralContoursNodelet::ReconfigureServer  [private] | 
Definition at line 70 of file general_contours_nodelet.cpp.
| void opencv_apps::GeneralContoursNodelet::doWork | ( | const sensor_msgs::ImageConstPtr & | msg, | 
| const std::string & | input_frame_from_msg | ||
| ) |  [inline, private] | 
Convert image to gray and blur it
Create window
Detect edges using Threshold
Find contours
Find the rotated rectangles and ellipses for each contour
Draw contours + rotated rects + ellipses
Create a Trackbar for user to enter threshold
Definition at line 111 of file general_contours_nodelet.cpp.
| const std::string& opencv_apps::GeneralContoursNodelet::frameWithDefault | ( | const std::string & | frame, | 
| const std::string & | image_frame | ||
| ) |  [inline, private] | 
Definition at line 89 of file general_contours_nodelet.cpp.
| void opencv_apps::GeneralContoursNodelet::imageCallback | ( | const sensor_msgs::ImageConstPtr & | msg | ) |  [inline, private] | 
Definition at line 101 of file general_contours_nodelet.cpp.
| void opencv_apps::GeneralContoursNodelet::imageCallbackWithInfo | ( | const sensor_msgs::ImageConstPtr & | msg, | 
| const sensor_msgs::CameraInfoConstPtr & | cam_info | ||
| ) |  [inline, private] | 
Definition at line 96 of file general_contours_nodelet.cpp.
| virtual void opencv_apps::GeneralContoursNodelet::onInit | ( | ) |  [inline, virtual] | 
Initialize nodehandles nh_ and pnh_. Subclass should call this method in its onInit method.
Reimplemented from opencv_apps::Nodelet.
Reimplemented in general_contours::GeneralContoursNodelet.
Definition at line 256 of file general_contours_nodelet.cpp.
| void opencv_apps::GeneralContoursNodelet::reconfigureCallback | ( | Config & | new_config, | 
| uint32_t | level | ||
| ) |  [inline, private] | 
Definition at line 83 of file general_contours_nodelet.cpp.
| void opencv_apps::GeneralContoursNodelet::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 239 of file general_contours_nodelet.cpp.
| static void opencv_apps::GeneralContoursNodelet::trackbarCallback | ( | int | , | 
| void * | |||
| ) |  [inline, static, private] | 
Definition at line 106 of file general_contours_nodelet.cpp.
| void opencv_apps::GeneralContoursNodelet::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 248 of file general_contours_nodelet.cpp.
Definition at line 64 of file general_contours_nodelet.cpp.
Definition at line 71 of file general_contours_nodelet.cpp.
| bool opencv_apps::GeneralContoursNodelet::debug_view_  [private] | 
Definition at line 75 of file general_contours_nodelet.cpp.
Definition at line 65 of file general_contours_nodelet.cpp.
Definition at line 62 of file general_contours_nodelet.cpp.
Definition at line 63 of file general_contours_nodelet.cpp.
| boost::shared_ptr<image_transport::ImageTransport> opencv_apps::GeneralContoursNodelet::it_  [private] | 
Definition at line 67 of file general_contours_nodelet.cpp.
| bool opencv_apps::GeneralContoursNodelet::need_config_update_ = false  [static, private] | 
Definition at line 81 of file general_contours_nodelet.cpp.
Definition at line 76 of file general_contours_nodelet.cpp.
| int opencv_apps::GeneralContoursNodelet::queue_size_  [private] | 
Definition at line 74 of file general_contours_nodelet.cpp.
| boost::shared_ptr<ReconfigureServer> opencv_apps::GeneralContoursNodelet::reconfigure_server_  [private] | 
Definition at line 72 of file general_contours_nodelet.cpp.
Definition at line 65 of file general_contours_nodelet.cpp.
| int opencv_apps::GeneralContoursNodelet::threshold_  [private] | 
Definition at line 78 of file general_contours_nodelet.cpp.
| std::string opencv_apps::GeneralContoursNodelet::window_name_  [private] | 
Definition at line 80 of file general_contours_nodelet.cpp.