| Public Member Functions | |
| void | detectCb (const sensor_msgs::ImageConstPtr &image_msg, const sensor_msgs::CameraInfoConstPtr &info_msg) | 
| DetectPlugAction (const std::string &name) | |
| void | goalCb () | 
| void | preemptCb () | 
| void | timeoutCb (const ros::TimerEvent &e) | 
| Protected Attributes | |
| actionlib::SimpleActionServer < pr2_plugs_msgs::VisionPlugDetectionAction > | as_ | 
| checkerboard_pose_estimation::RosDetector | detector_ | 
| image_transport::ImageTransport | it_ | 
| std::string | name_ | 
| ros::NodeHandle | nh_ | 
| tf::Stamped< tf::Pose > | plug_prior_ | 
| ros::Timer | pub_timer_ | 
| image_transport::CameraSubscriber | sub_ | 
| tf::TransformListener | tf_listener_ | 
Definition at line 9 of file vision_detect_plug.cpp.
| DetectPlugAction::DetectPlugAction | ( | const std::string & | name | ) |  [inline] | 
Definition at line 12 of file vision_detect_plug.cpp.
| void DetectPlugAction::detectCb | ( | const sensor_msgs::ImageConstPtr & | image_msg, | 
| const sensor_msgs::CameraInfoConstPtr & | info_msg | ||
| ) |  [inline] | 
Definition at line 72 of file vision_detect_plug.cpp.
| void DetectPlugAction::goalCb | ( | ) |  [inline] | 
Definition at line 43 of file vision_detect_plug.cpp.
| void DetectPlugAction::preemptCb | ( | ) |  [inline] | 
Definition at line 64 of file vision_detect_plug.cpp.
| void DetectPlugAction::timeoutCb | ( | const ros::TimerEvent & | e | ) |  [inline] | 
Definition at line 32 of file vision_detect_plug.cpp.
| actionlib::SimpleActionServer<pr2_plugs_msgs::VisionPlugDetectionAction> DetectPlugAction::as_  [protected] | 
Definition at line 94 of file vision_detect_plug.cpp.
Definition at line 99 of file vision_detect_plug.cpp.
| image_transport::ImageTransport DetectPlugAction::it_  [protected] | 
Definition at line 93 of file vision_detect_plug.cpp.
| std::string DetectPlugAction::name_  [protected] | 
Definition at line 95 of file vision_detect_plug.cpp.
| ros::NodeHandle DetectPlugAction::nh_  [protected] | 
Definition at line 92 of file vision_detect_plug.cpp.
| tf::Stamped<tf::Pose> DetectPlugAction::plug_prior_  [protected] | 
Definition at line 98 of file vision_detect_plug.cpp.
| ros::Timer DetectPlugAction::pub_timer_  [protected] | 
Definition at line 100 of file vision_detect_plug.cpp.
Definition at line 96 of file vision_detect_plug.cpp.
| tf::TransformListener DetectPlugAction::tf_listener_  [protected] | 
Definition at line 97 of file vision_detect_plug.cpp.