fractalposetracker.h
Go to the documentation of this file.
1 #include <opencv2/imgproc/imgproc.hpp>
2 #include "../picoflann.h"
3 #include "../cameraparameters.h"
4 #include "../markerdetector.h"
5 #include "fractalmarkerset.h"
6 #include "../aruco_export.h"
7 namespace aruco
8 {
9 
10 
11 void kfilter(std::vector<cv::KeyPoint> &kpoints);
12 
21 void assignClass(const cv::Mat &im, std::vector<cv::KeyPoint> &kpoints,
22  float sizeNorm = 0.f, int wsize = 5);
23 
25 {
26  inline float operator()(const cv::KeyPoint &elem, int dim) const
27  {
28  return dim == 0 ? elem.pt.x : elem.pt.y;
29  }
30  inline float operator()(const cv::Point2f &elem, int dim) const
31  {
32  return dim == 0 ? elem.x : elem.y;
33  }
34 };
35 
37 {
38 public:
46  void setParams(const CameraParameters &cam_params, const FractalMarkerSet &msconf,
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);
70 
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.2f, float _thresInliers = 0.7f);
85 
93  void drawKeyPoints(const cv::Mat image, std::vector<cv::KeyPoint> kpoints,
94  bool text = false, bool transf = false);
95 
104  bool fractalRefinement(const cv::Ptr<MarkerDetector> markerDetector, int markerWarpPix = 10);
105 
106  // return the rotation vector. Returns an empty matrix if last call to estimatePose returned false
107  const cv::Mat getRvec() const
108  {
109  return _rvec;
110  }
111 
112  // return the translation vector. Returns an empty matrix if last call to estimatePose returned false
113  const cv::Mat getTvec() const
114  {
115  return _tvec;
116  }
117 
118  // return all corners from fractal marker
119  const std::vector<cv::Point3f> getInner3d()
120  {
121  return _innerp3d;
122  }
123 
124  // is the pose valid?
125  bool isPoseValid() const
126  {
127  return !_rvec.empty() && !_tvec.empty();
128  }
129 
131  {
132  return _fractalMarker;
133  }
134 
135 private:
136  FractalMarkerSet _fractalMarker; // FractalMarkerSet configuration
137  aruco::CameraParameters _cam_params; // Camera parameters.
138  cv::Mat _rvec, _tvec; // current poses
139  std::map<int, std::vector<cv::Point3f>> _id_innerp3d; // Id_marker-Inners_corners
140  std::vector<cv::Point3f> _innerp3d; // All inners corners
141  std::vector<cv::KeyPoint> _innerkpoints; // All inners keypoints
143  std::map<int, double> _id_radius; // Idmarker_Radius(Optimus)
144  std::map<int, float> _id_area; // Idmarker_projectedArea(Optimus)
145  float _preRadius = 0; // radius used previous iteration
146 };
147 } // namespace aruco
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
f
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
Parameters of the camera.
const cv::Mat getRvec() const
picoflann::KdTreeIndex< 2, PicoFlann_KeyPointAdapter > _kdtree
const std::vector< cv::Point3f > getInner3d()
FractalMarkerSet getFractal()
#define ARUCO_EXPORT
Definition: aruco_export.h:30
float operator()(const cv::KeyPoint &elem, int dim) const
std::map< int, float > _id_area
std::map< int, double > _id_radius


aruco
Author(s): Rafael Muñoz Salinas , Bence Magyar
autogenerated on Fri Nov 25 2022 04:02:23