continuous_detector.h
Go to the documentation of this file.
1 
43 #ifndef APRILTAG_ROS_CONTINUOUS_DETECTOR_H
44 #define APRILTAG_ROS_CONTINUOUS_DETECTOR_H
45 
47 
48 #include <memory>
49 #include <mutex>
50 
51 #include <nodelet/nodelet.h>
52 #include <ros/service_server.h>
53 #include <std_srvs/Empty.h>
54 
55 namespace apriltag_ros
56 {
57 
59 {
60  public:
61  ContinuousDetector() = default;
62  ~ContinuousDetector() = default;
63 
64  void onInit();
65 
66  void imageCallback(const sensor_msgs::ImageConstPtr& image_rect,
67  const sensor_msgs::CameraInfoConstPtr& camera_info);
68 
69  void refreshTagParameters();
70 
71  private:
72  std::mutex detection_mutex_;
73  std::shared_ptr<TagDetector> tag_detector_;
76 
77  std::shared_ptr<image_transport::ImageTransport> it_;
81 
83  bool refreshParamsCallback(std_srvs::Empty::Request& req, std_srvs::Empty::Response& res);
84 };
85 
86 } // namespace apriltag_ros
87 
88 #endif // APRILTAG_ROS_CONTINUOUS_DETECTOR_H
ros::ServiceServer refresh_params_service_
image_transport::CameraSubscriber camera_image_subscriber_
std::shared_ptr< TagDetector > tag_detector_
bool refreshParamsCallback(std_srvs::Empty::Request &req, std_srvs::Empty::Response &res)
image_transport::Publisher tag_detections_image_publisher_
std::shared_ptr< image_transport::ImageTransport > it_
void imageCallback(const sensor_msgs::ImageConstPtr &image_rect, const sensor_msgs::CameraInfoConstPtr &camera_info)


apriltag_ros
Author(s): Danylo Malyuta
autogenerated on Tue Mar 28 2023 02:10:49