markerdetector.h
Go to the documentation of this file.
1 
17 #ifndef _ARUCO_MarkerDetector_H
18 #define _ARUCO_MarkerDetector_H
19 
20 #include "aruco_export.h"
21 #include <opencv2/core/core.hpp>
22 #include <cstdio>
23 #include <iostream>
24 #include <queue>
25 #include <mutex>
26 #include <condition_variable>
27 #include <vector>
28 #include <map>
29 #include "marker.h"
30 
31 #include <opencv2/imgproc/imgproc.hpp>
32 
33 namespace aruco
34 {
35 
60 enum DetectionMode : int
61 {
62  DM_NORMAL = 0,
63  DM_FAST = 1,
65 };
75 {
79 };
80 
81 
82 class CameraParameters;
83 class MarkerLabeler;
85 typedef Marker MarkerCandidate;
86 
92 {
93  friend class MarkerDetector_Impl;
94 
95 public:
96  enum ThresMethod : int
97  {
98  THRES_ADAPTIVE = 0,
99  THRES_AUTO_FIXED = 1
100  };
101 
105  {
127  void setDetectionMode(DetectionMode dm, float minMarkerSize);
128 
132  void detectEnclosedMarkers(bool do_)
133  {
134  enclosedMarker = do_;
135  }
136 
147  void setCornerRefinementMethod(CornerRefinementMethod method);
148 
149 
150  //-----------------------------------------------------------------------------
151  // Below this point you probably should not use the functions
154  void setThresholdMethod(ThresMethod method, int thresHold = -1, int wsize = -1,
155  int wsize_range = 0);
156 
157 
158 
159  void setAutoSizeSpeedUp(bool v, float Ts = 0.25)
160  {
161  autoSize = v;
162  ts = Ts;
163  }
164  bool getAutoSizeSpeedUp() const
165  {
166  return autoSize;
167  }
168 
169 
170 
171  void save(cv::FileStorage &fs) const;
172  void load(cv::FileStorage &fs);
173 
174  void toStream(std::ostream &str) const;
175  void fromStream(std::istream &str);
176 
177  static std::string toString(DetectionMode dm);
178  static DetectionMode getDetectionModeFromString(const std::string &str);
179  static std::string toString(CornerRefinementMethod dm);
180  static CornerRefinementMethod getCornerRefinementMethodFromString(const std::string &str);
181  static std::string toString(ThresMethod dm);
182  static ThresMethod getCornerThresMethodFromString(const std::string &str);
183 
184  // Detection mode
185 
186  DetectionMode detectMode = DM_NORMAL;
187 
188  // maximum number of parallel threads
189  int maxThreads = 1; //-1 means all
190 
191  // border around image limits in which corners are not allowed to be detected. (0,1)
192  float borderDistThres = 0.015f;
193  int lowResMarkerSize = 20; // minimum size of a marker in the low resolution image
194 
195  // minimum size of a contour lenght. We use the following formula
196  // minLenght= min ( _minSize_pix , _minSize* Is)*4
197  // being Is=max(imageWidth,imageHeight)
198  // the value _minSize are normalized, thus, depends on camera image size
199  // However, _minSize_pix is expressed in pixels (you can use the one you prefer)
200  float minSize = -1; // tau_i in paper
201  int minSize_pix = -1;
202  bool enclosedMarker = false; // special treatment for enclosed markers
203  float error_correction_rate = 0;
204  std::string dictionary = "ALL_DICTS";
205  // threshold methods
206  ThresMethod thresMethod = THRES_ADAPTIVE;
207  int NAttemptsAutoThresFix =
208  3; // number of times that tries a random threshold in case of THRES_AUTO_FIXED
209  int trackingMinDetections = 0; // no tracking
210 
211 
212  // Threshold parameters
213  int AdaptiveThresWindowSize = -1, ThresHold = 7, AdaptiveThresWindowSize_range = 0;
214  // size of the image passedta to the MarkerLabeler
215  int markerWarpPixSize = 5; // tau_c in paper
216 
218  // enable/disables the method for automatic size estimation for speed up
219  bool autoSize = false;
220  float ts =
221  0.25f; //$\tau_s$ is a factor in the range $(0,1]$ that accounts for the camera
222  //motion speed. For instance, when $\tau_s=0.1$, it means that in the next
223  //frame, $\tau_i$ is such that markers $10\%$ smaller than the smallest
224  //marker in the current image will be seek. To avoid loosing track of the
225  //markers. If no markers are detected in a frame, $\tau_i$ is set to zero
226  //for the next frame so that markers of any size can be detected.
234  float pyrfactor = 2;
235  int closingSize =
236  0; // enables/disables morph closing operation. The actual param used is closingSize*2+1
237 
238  private:
239  static void _toStream(const std::string &strg, std::ostream &str);
240  static void _fromStream(std::string &strg, std::istream &str);
241  template <typename Type>
242  static bool attemtpRead(const std::string &name, Type &var, cv::FileStorage &fs)
243  {
244  if (fs[name].type() != cv::FileNode::NONE)
245  {
246  fs[name] >> var;
247  return true;
248  }
249  return false;
250  }
251  };
252 
256  MarkerDetector();
264  MarkerDetector(int dict_type, float error_correction_rate = 0);
265  MarkerDetector(std::string dict_type, float error_correction_rate = 0);
266 
269  void saveParamsToFile(const std::string &path) const;
270 
273  void loadParamsFromFile(const std::string &path);
274 
275 
278  ~MarkerDetector();
302  void setDetectionMode(DetectionMode dm, float minMarkerSize = 0);
305  DetectionMode getDetectionMode();
322  std::vector<aruco::Marker> detect(const cv::Mat &input);
323  std::vector<aruco::Marker> detect(const cv::Mat &input, const CameraParameters &camParams,
324  float markerSizeMeters, bool setYPerperdicular = false,
325  bool correctFisheye = false);
326 
340  void detect(const cv::Mat &input, std::vector<Marker> &detectedMarkers,
341  CameraParameters camParams, float markerSizeMeters = -1,
342  bool setYPerperdicular = false, bool correctFisheye = false);
343 
364  void detect(const cv::Mat &input, std::vector<Marker> &detectedMarkers,
365  cv::Mat camMatrix = cv::Mat(), cv::Mat distCoeff = cv::Mat(),
366  cv::Mat extrinsics = cv::Mat(), float markerSizeMeters = -1,
367  bool setYPerperdicular = false, bool correctFisheye = false);
368 
371  Params getParameters() const;
374  Params &getParameters();
390  void setDictionary(std::string dict_type, float error_correction_rate = 0);
391 
401  void setDictionary(int dict_type, float error_correction_rate = 0);
402 
407  cv::Mat getThresholdedImage(uint32_t idx = 0);
410  // size_t getNhresholdedImages()const{return _thres_Images.size();}
411 
412 
413 
418 
424  void setMarkerLabeler(cv::Ptr<MarkerLabeler> detector);
425  cv::Ptr<MarkerLabeler> getMarkerLabeler();
426 
427 
431  std::vector<MarkerCandidate> getCandidates() const;
432 
433  std::vector<cv::Mat> getImagePyramid();
434  /*
435  * @param corners vectors of vectors
436  */
437  void cornerUpsample(std::vector<std::vector<cv::Point2f> > &corners, cv::Size lowResImageSize);
438  void cornerUpsample(std::vector<Marker> &corners, cv::Size lowResImageSize);
439 
448  bool warp(cv::Mat &in, cv::Mat &out, cv::Size size, std::vector<cv::Point2f> points);
449 
450 
451  // serialization in binary mode
452  void toStream(std::ostream &str) const;
453  void fromStream(std::istream &str);
454  // configure the detector from a set of parameters
455  void setParameters(const Params &params);
456 
457 
458 
459 private:
461 };
462 }; // namespace aruco
463 #endif
aruco::DM_FAST
@ DM_FAST
Definition: markerdetector.h:63
aruco::DM_VIDEO_FAST
@ DM_VIDEO_FAST
Definition: markerdetector.h:64
aruco::MarkerDetector::Params::attemtpRead
static bool attemtpRead(const std::string &name, Type &var, cv::FileStorage &fs)
Definition: markerdetector.h:242
aruco::CORNER_SUBPIX
@ CORNER_SUBPIX
Definition: markerdetector.h:76
aruco::CameraParameters
Parameters of the camera.
Definition: cameraparameters.h:29
aruco::MarkerCandidate
Marker MarkerCandidate
Definition: markerdetector.h:84
marker.h
aruco::CornerRefinementMethod
CornerRefinementMethod
Definition: markerdetector.h:74
aruco::MarkerDetector_Impl
Main class for marker detection.
Definition: markerdetector_impl.h:41
aruco_export.h
aruco::DM_NORMAL
@ DM_NORMAL
Definition: markerdetector.h:62
aruco::Marker
Definition: marker.h:35
aruco::MarkerDetector::ThresMethod
ThresMethod
Definition: markerdetector.h:96
aruco::CORNER_LINES
@ CORNER_LINES
Definition: markerdetector.h:77
aruco::MarkerDetector::Params
Definition: markerdetector.h:104
ARUCO_EXPORT
#define ARUCO_EXPORT
Definition: aruco_export.h:30
aruco::MarkerDetector::Params::detectEnclosedMarkers
void detectEnclosedMarkers(bool do_)
Definition: markerdetector.h:132
aruco::MarkerDetector
Main class for marker detection.
Definition: markerdetector.h:91
aruco
Definition: cameraparameters.h:24
aruco::DetectionMode
DetectionMode
The DetectionMode enum defines the different possibilities for detection. Specifies the detection mod...
Definition: markerdetector.h:60
aruco::MarkerDetector::Params::setAutoSizeSpeedUp
void setAutoSizeSpeedUp(bool v, float Ts=0.25)
Definition: markerdetector.h:159
aruco::CORNER_NONE
@ CORNER_NONE
Definition: markerdetector.h:78
aruco::MarkerDetector::Params::getAutoSizeSpeedUp
bool getAutoSizeSpeedUp() const
Definition: markerdetector.h:164
aruco::MarkerDetector::_impl
MarkerDetector_Impl * _impl
Definition: markerdetector.h:460


aruco
Author(s): Rafael Muñoz Salinas , Bence Magyar
autogenerated on Sat Sep 23 2023 02:26:45