00001 00018 #ifndef MARKER_DETECTION_H 00019 #define MARKER_DETECTION_H 00020 00021 #include "aruco/aruco.h" 00022 #include <geometry_msgs/Pose.h> 00023 #include <sensor_msgs/CameraInfo.h> 00024 #include <asr_aruco_marker_recognition/ArucoMarkerRecognitionConfig.h> 00025 00026 namespace aruco_marker_recognition { 00027 00028 using namespace asr_aruco_marker_recognition; 00029 00033 class MarkerDetection { 00034 00035 00036 private: 00037 00039 double DEFAULT_MARKER_SIZE = 0.1; 00040 00042 double marker_size_; 00043 00045 aruco::CameraParameters cam_params_left_; 00046 00048 aruco::CameraParameters cam_params_right_; 00049 00050 00051 public: 00053 enum CameraId { cam_left, cam_right }; 00054 00058 MarkerDetection() : MarkerDetection(DEFAULT_MARKER_SIZE) {} 00059 00064 MarkerDetection(double marker_size); 00065 00072 std::vector<aruco::Marker> detect(const cv::Mat &image, CameraId id, const ArucoMarkerRecognitionConfig &config); 00073 00079 void setCameraParameters(const sensor_msgs::CameraInfo &cam_params_left, const sensor_msgs::CameraInfo &cam_params_right); 00080 }; 00081 00082 } 00083 00084 00085 #endif 00086 00087