Go to the documentation of this file.
43 #include <opencv2/aruco.hpp>
47 class HandEyeArucoTarget :
public HandEyeTargetBase
60 virtual bool setTargetIntrinsicParams(
int markers_x,
int markers_y,
int marker_size,
int separation,
int border_bits,
61 const std::string& dictionary_id);
63 virtual bool setTargetDimension(
double marker_measured_size,
double marker_measured_separation);
virtual bool createTargetImage(cv::Mat &image) const override
Create an target image, so that the target can be viewed and printed.
virtual bool setTargetDimension(double marker_measured_size, double marker_measured_separation)
virtual bool setTargetIntrinsicParams(int markers_x, int markers_y, int marker_size, int separation, int border_bits, const std::string &dictionary_id)
cv::aruco::PREDEFINED_DICTIONARY_NAME dictionary_id_
~HandEyeArucoTarget()=default
double marker_separation_real_
std::map< std::string, cv::aruco::PREDEFINED_DICTIONARY_NAME > marker_dictionaries_
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...
virtual bool initialize() override
Initialize handeye target. Call after setting the parameters.