1 #include <opencv2/imgproc/imgproc.hpp> 2 #include "../picoflann.h" 3 #include "../cameraparameters.h" 4 #include "../markerdetector.h" 6 #include "../aruco_export.h" 11 void kfilter(std::vector<cv::KeyPoint> &kpoints);
21 void assignClass(
const cv::Mat &im, std::vector<cv::KeyPoint> &kpoints,
22 float sizeNorm = 0.f,
int wsize = 5);
26 inline float operator()(
const cv::KeyPoint &elem,
int dim)
const 28 return dim == 0 ? elem.pt.x : elem.pt.y;
30 inline float operator()(
const cv::Point2f &elem,
int dim)
const 32 return dim == 0 ? elem.x : elem.y;
47 const float markerSize = -1);
56 bool fractalInnerPose(
const cv::Ptr<MarkerDetector> markerDetector,
57 const std::vector<aruco::Marker> &markers,
bool refinement =
true);
68 bool ROI(
const std::vector<cv::Mat> imagePyramid, cv::Mat &img,
69 std::vector<cv::Point2f> &innerPoints2d, cv::Point2f &offset,
float &ratio);
81 cv::Mat fractal_solve_ransac(
int ninners,
82 std::vector<std::pair<uint, std::vector<uint>>> inner_kpnt,
83 std::vector<cv::KeyPoint> kpnts, uint32_t maxIter = 500,
84 float _minInliers = 0.2
f,
float _thresInliers = 0.7
f);
93 void drawKeyPoints(
const cv::Mat image, std::vector<cv::KeyPoint> kpoints,
94 bool text =
false,
bool transf =
false);
104 bool fractalRefinement(
const cv::Ptr<MarkerDetector> markerDetector,
int markerWarpPix = 10);
127 return !_rvec.empty() && !_tvec.empty();
132 return _fractalMarker;
145 float _preRadius = 0;
std::vector< cv::KeyPoint > _innerkpoints
void assignClass(const cv::Mat &im, std::vector< cv::KeyPoint > &kpoints, float sizeNorm=0.f, int wsize=5)
assignClass
std::map< int, std::vector< cv::Point3f > > _id_innerp3d
const cv::Mat getTvec() const
std::vector< cv::Point3f > _innerp3d
void kfilter(std::vector< cv::KeyPoint > &kpoints)
float operator()(const cv::Point2f &elem, int dim) const
aruco::CameraParameters _cam_params
FractalMarkerSet _fractalMarker
Parameters of the camera.
const cv::Mat getRvec() const
picoflann::KdTreeIndex< 2, PicoFlann_KeyPointAdapter > _kdtree
const std::vector< cv::Point3f > getInner3d()
FractalMarkerSet getFractal()
float operator()(const cv::KeyPoint &elem, int dim) const
std::map< int, float > _id_area
std::map< int, double > _id_radius