17 #ifndef ARUCO_POSETRACKER 18 #define ARUCO_POSETRACKER 26 #include <opencv2/core/core.hpp> 82 float minErrorRatio = 10 );
102 double solve_pnp(
const std::vector<cv::Point3f>& p3d,
103 const std::vector<cv::Point2f>& p2d,
const cv::Mat& cam_matrix,
104 const cv::Mat& dist, cv::Mat& r_io, cv::Mat& t_io);
120 float markerSize = -1);
138 bool estimatePose(
const std::vector<Marker>& v_m);
160 _maxTranslation = maxTranslation;
161 _maxAngle = maxAngle;
166 aruco_minerrratio_valid = minErrorRatio;
180 cv::Mat relocalization(
const std::vector<Marker>& v_m);
184 float _maxTranslation = -1, _maxAngle = -1;
const cv::Mat getTvec() const
float aruco_minerrratio_valid
cv::Mat getRTMatrix(const cv::Mat &R_, const cv::Mat &T_, int forceType)
const cv::Mat getRvec() const
void setMaxTrackingDifference(float maxTranslation, float maxAngle)
std::map< uint32_t, cv::Mat > marker_m2g
const cv::Mat getRvec() const
Parameters of the camera.
const cv::Mat getTvec() const
void setMinErrorRatio(float minErrorRatio)
std::map< int, Marker3DInfo > _map_mm
This class defines a set of markers whose locations are attached to a common reference system...
aruco::CameraParameters _cam_params