Go to the documentation of this file.
43 #include <opencv2/aruco/charuco.hpp>
47 class HandEyeCharucoTarget :
public HandEyeTargetBase
61 int border_size_bits,
int margin_size_pixels,
const std::string& dictionary_id);
cv::aruco::PREDEFINED_DICTIONARY_NAME dictionary_id_
virtual bool createTargetImage(cv::Mat &image) const override
Create an target image, so that the target can be viewed and printed.
std::map< std::string, cv::aruco::PREDEFINED_DICTIONARY_NAME > marker_dictionaries_
~HandEyeCharucoTarget()=default
virtual bool setTargetDimension(double board_size_meters, double marker_size_meters)
virtual bool setTargetIntrinsicParams(int markers_x, int markers_y, int marker_size_pixels, int square_size_pixels, int border_size_bits, int margin_size_pixels, const std::string &dictionary_id)
double marker_size_meters_
virtual bool initialize() override
Initialize handeye target. Call after setting the parameters.
double board_size_meters_
std::mutex charuco_mutex_
virtual bool detectTargetPose(cv::Mat &image) override
Given an image containing a target captured from a camera view point, get the target pose with respec...