Class ArucoDetector

Class Documentation

class ArucoDetector

Public Functions

ArucoDetector() = delete
explicit ArucoDetector(rclcpp::Logger logger)
void set_dictionary(const std::string &dictionary_name)
void set_detector_parameters(const DetectorParams &params)
void set_aruco_parameters(const cv::Ptr<cv::aruco::DetectorParameters> &params)
void set_camera_intrinsics(const cv::Mat &camera_matrix, const cv::Mat &dist_coeffs)
void update_camera_info(const sensor_msgs::msg::CameraInfo &cam_info, bool image_is_rectified)
void get_intrinsics(cv::Mat &camera_matrix, cv::Mat &dist_coeffs) const
void set_boards(const std::vector<std::pair<std::string, cv::Ptr<cv::aruco::Board>>> &boards)
cv::Ptr<cv::aruco::Dictionary> get_dictionary()
void detect(const cv::Mat &image, std::vector<int> &marker_ids, std::vector<std::vector<cv::Point2f>> &marker_corners) const

Detects markers in the given image.

Parameters:
  • image – Input image

  • marker_ids – Output vector of detected marker IDs

  • marker_corners – Output vector of detected marker corners

void estimate_marker_poses(const std::vector<int> &marker_ids, const std::vector<std::vector<cv::Point2f>> &marker_corners, std::vector<aruco_opencv_msgs::msg::MarkerPose> &marker_poses, std::vector<cv::Vec3d> &rvecs, std::vector<cv::Vec3d> &tvecs) const

Estimates poses of detected markers.

Parameters:
  • marker_ids – IDs of detected markers

  • marker_corners – Corners of detected markers

  • marker_poses – Output vector of estimated marker poses

  • rvecs – Output rotation vectors of estimated poses

  • tvecs – Output translation vectors of estimated poses

void estimate_board_poses(const std::vector<int> &marker_ids, const std::vector<std::vector<cv::Point2f>> &marker_corners, std::vector<aruco_opencv_msgs::msg::BoardPose> &board_poses, std::vector<cv::Vec3d> &rvecs, std::vector<cv::Vec3d> &tvecs) const

Estimates poses of known boards from detected markers.

Parameters:
  • marker_ids – IDs of detected markers

  • marker_corners – Corners of detected markers

  • board_poses – Output vector of estimated board poses

  • rvecs – Output rotation vectors of estimated board poses

  • tvecs – Output translation vectors of estimated board poses