#include <continuous_detector.h>

Public Member Functions | |
| ContinuousDetector ()=default | |
| void | imageCallback (const sensor_msgs::ImageConstPtr &image_rect, const sensor_msgs::CameraInfoConstPtr &camera_info) |
| void | onInit () |
| void | refreshTagParameters () |
| ~ContinuousDetector ()=default | |
Public Member Functions inherited from nodelet::Nodelet | |
| void | init (const std::string &name, const M_string &remapping_args, const V_string &my_argv, ros::CallbackQueueInterface *st_queue=NULL, ros::CallbackQueueInterface *mt_queue=NULL) |
| Nodelet () | |
| virtual | ~Nodelet () |
Private Member Functions | |
| bool | refreshParamsCallback (std_srvs::Empty::Request &req, std_srvs::Empty::Response &res) |
Private Attributes | |
| image_transport::CameraSubscriber | camera_image_subscriber_ |
| cv_bridge::CvImagePtr | cv_image_ |
| std::mutex | detection_mutex_ |
| bool | draw_tag_detections_image_ |
| std::shared_ptr< image_transport::ImageTransport > | it_ |
| ros::ServiceServer | refresh_params_service_ |
| image_transport::Publisher | tag_detections_image_publisher_ |
| ros::Publisher | tag_detections_publisher_ |
| std::shared_ptr< TagDetector > | tag_detector_ |
Additional Inherited Members | |
Protected Member Functions inherited from nodelet::Nodelet | |
| ros::CallbackQueueInterface & | getMTCallbackQueue () const |
| ros::NodeHandle & | getMTNodeHandle () const |
| ros::NodeHandle & | getMTPrivateNodeHandle () const |
| const V_string & | getMyArgv () const |
| const std::string & | getName () const |
| ros::NodeHandle & | getNodeHandle () const |
| ros::NodeHandle & | getPrivateNodeHandle () const |
| const M_string & | getRemappingArgs () const |
| ros::CallbackQueueInterface & | getSTCallbackQueue () const |
| std::string | getSuffixedName (const std::string &suffix) const |
Definition at line 58 of file continuous_detector.h.
|
default |
|
default |
| void apriltag_ros::ContinuousDetector::imageCallback | ( | const sensor_msgs::ImageConstPtr & | image_rect, |
| const sensor_msgs::CameraInfoConstPtr & | camera_info | ||
| ) |
Definition at line 89 of file continuous_detector.cpp.
|
virtual |
Implements nodelet::Nodelet.
Definition at line 40 of file continuous_detector.cpp.
|
private |
Definition at line 82 of file continuous_detector.cpp.
| void apriltag_ros::ContinuousDetector::refreshTagParameters | ( | ) |
Definition at line 72 of file continuous_detector.cpp.
|
private |
Definition at line 78 of file continuous_detector.h.
|
private |
Definition at line 75 of file continuous_detector.h.
|
private |
Definition at line 72 of file continuous_detector.h.
|
private |
Definition at line 74 of file continuous_detector.h.
|
private |
Definition at line 77 of file continuous_detector.h.
|
private |
Definition at line 82 of file continuous_detector.h.
|
private |
Definition at line 79 of file continuous_detector.h.
|
private |
Definition at line 80 of file continuous_detector.h.
|
private |
Definition at line 73 of file continuous_detector.h.