markerdetector_impl.h
Go to the documentation of this file.
1 
17 #ifndef _ARUCO_MarkerDetector_Impl_H
18 #define _ARUCO_MarkerDetector_Impl_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 #include "markerdetector.h"
31 #include <opencv2/imgproc/imgproc.hpp>
32 
33 namespace aruco
34 {
35 
36 class CameraParameters;
37 class MarkerLabeler;
42 {
43  friend class MarkerDetector;
44 
45 public:
57  MarkerDetector_Impl(int dict_type, float error_correction_rate = 0);
58  MarkerDetector_Impl(std::string dict_type, float error_correction_rate = 0);
59 
62  void saveParamsToFile(const std::string& path) const;
63 
66  void loadParamsFromFile(const std::string& path);
67 
68 
95  void setDetectionMode(DetectionMode dm, float minMarkerSize = 0);
115  std::vector<aruco::Marker> detect(const cv::Mat& input);
116  std::vector<aruco::Marker> detect(const cv::Mat& input, const CameraParameters& camParams,
117  float markerSizeMeters, bool setYPerperdicular = false,
118  bool correctFisheye = false);
119 
133  void detect(const cv::Mat& input, std::vector<Marker>& detectedMarkers,
134  CameraParameters camParams, float markerSizeMeters = -1,
135  bool setYPerperdicular = false, bool correctFisheye = false);
136 
157  void detect(const cv::Mat& input, std::vector<Marker>& detectedMarkers,
158  cv::Mat camMatrix = cv::Mat(), cv::Mat distCoeff = cv::Mat(),
159  cv::Mat extrinsics = cv::Mat(), float markerSizeMeters = -1,
160  bool setYPerperdicular = false, bool correctFisheye = false);
161 
162 
166  {
167  return _params;
168  }
172  {
173  return _params;
174  }
190  void setDictionary(std::string dict_type, float error_correction_rate = 0);
191 
201  void setDictionary(int dict_type, float error_correction_rate = 0);
202 
207  cv::Mat getThresholdedImage(uint32_t idx = 0);
210  // size_t getNhresholdedImages()const{return _thres_Images.size();}
211 
212 
213 
218 
224  void setMarkerLabeler(cv::Ptr<MarkerLabeler> detector);
225  cv::Ptr<MarkerLabeler> getMarkerLabeler()
226  {
227  return markerIdDetector;
228  }
230 
231 
235  std::vector<MarkerCandidate> getCandidates() const
236  {
237  return _candidates_wcontour;
238  }
239 
248  bool warp(cv::Mat& in, cv::Mat& out, cv::Size size, std::vector<cv::Point2f> points);
249 
250 
251  // serialization in binary mode
252  void toStream(std::ostream& str) const;
253  void fromStream(std::istream& str);
254  // configure the detector from a set of parameters
255  void setParameters(const MarkerDetector::Params& params);
256 
257  std::vector<cv::Mat> getImagePyramid()
258  {
259  return imagePyramid;
260  }
261 
262 
263 
264 private:
265  // obfuscate start
266 
267  // operating params
269 
270  // Images
271  cv::Mat grey, thres;
272  // pointer to the function that analizes a rectangular region so as to detect its internal marker
273  cv::Ptr<MarkerLabeler> markerIdDetector;
276  int perimeter(const std::vector<cv::Point2f>& a);
277 
278  // auxiliar functions to perform LINES refinement
279  void interpolate2Dline(const std::vector<cv::Point2f>& inPoints, cv::Point3f& outLine);
280  cv::Point2f getCrossPoint(const cv::Point3f& line1, const cv::Point3f& line2);
281  void distortPoints(std::vector<cv::Point2f> in, std::vector<cv::Point2f>& out,
282  const cv::Mat& camMatrix, const cv::Mat& distCoeff);
283 
284  // returns the number of pixels that the smallest and largest allowed markers have
285  int getMinMarkerSizePix(cv::Size orginput_imageSize) const;
286 
287  // returns the markerWarpSize
288  int getMarkerWarpSize();
294  template <typename T>
295  void removeElements(std::vector<T>& vinout, const std::vector<bool>& toRemove)
296  {
297  // remove the invalid ones by setting the valid in the positions left by the invalids
298  size_t indexValid = 0;
299  for (size_t i = 0; i < toRemove.size(); i++)
300  {
301  if (!toRemove[i])
302  {
303  if (indexValid != i)
304  vinout[indexValid] = vinout[i];
305  indexValid++;
306  }
307  }
308  vinout.resize(indexValid);
309  }
310 
311 
312  template <typename T>
313  void joinVectors(std::vector<std::vector<T>>& vv, std::vector<T>& v, bool clearv = false)
314  {
315  if (clearv)
316  v.clear();
317  for (size_t i = 0; i < vv.size(); i++)
318  for (size_t j = 0; j < vv[i].size(); j++)
319  v.push_back(vv[i][j]);
320  }
321 
322  std::vector<cv::Mat> imagePyramid;
323  void enlargeMarkerCandidate(MarkerCandidate& cand, int fact = 1);
324 
325  void cornerUpsample(std::vector<std::vector<cv::Point2f>>& MarkerCanditates,
326  cv::Size lowResImageSize);
327  void cornerUpsample(std::vector<Marker>& MarkerCanditates, cv::Size lowResImageSize);
328 
329 
330 
331  void buildPyramid(std::vector<cv::Mat>& imagePyramid, const cv::Mat& grey, int minSize);
332 
333 
334 
335  std::vector<aruco::MarkerCandidate> thresholdAndDetectRectangles(const cv::Mat& input,
336  int thres_param1,
337  int thres_param2, bool erode,
338  cv::Mat& auxThresImage);
339  std::vector<aruco::MarkerCandidate> thresholdAndDetectRectangles(const cv::Mat& image);
340  std::vector<aruco::MarkerCandidate> prefilterCandidates(std::vector<MarkerCandidate>& candidates,
341  cv::Size orgImageSize);
342 
343 
344  std::vector<cv::Mat> _thres_Images;
345  std::vector<std::vector<MarkerCandidate>> _vcandidates;
346  // std::vector<std::vector<cv::Point2f > > _candidates;
347  std::vector<MarkerCandidate> _candidates_wcontour;
348  std::vector<Marker> _prevMarkers; // employed for tracking
349  std::map<int, int> marker_ndetections; // used to keeps track only of markers with a
350  // minimum number of detections
351 
352  // graphical debug
353  void drawApproxCurve(cv::Mat& in, std::vector<cv::Point>& approxCurve, cv::Scalar color,
354  int thickness = 1);
355  void drawContour(cv::Mat& in, std::vector<cv::Point>& contour, cv::Scalar);
356  void drawAllContours(cv::Mat input, std::vector<std::vector<cv::Point>>& contours);
357  void draw(cv::Mat out, const std::vector<Marker>& markers);
358 
359 
360 
362  {
366  };
368  {
369  int inIdx, outIdx;
372  };
374 
375  // thread safe queue to implement producer-consumer
376  template <typename T>
377  class Queue
378  {
379  public:
380  T pop()
381  {
382  std::unique_lock<std::mutex> mlock(mutex_);
383  while (queue_.empty())
384  {
385  cond_.wait(mlock);
386  }
387  auto item = queue_.front();
388  queue_.pop();
389  return item;
390  }
391 
392  void push(const T& item)
393  {
394  std::unique_lock<std::mutex> mlock(mutex_);
395  queue_.push(item);
396  mlock.unlock();
397  cond_.notify_one();
398  }
399 
400  size_t size()
401  {
402  std::unique_lock<std::mutex> mlock(mutex_);
403  size_t s = queue_.size();
404  return s;
405  }
406 
407  private:
408  std::queue<T> queue_;
409  std::mutex mutex_;
410  std::condition_variable cond_;
411  };
413  void refineCornerWithContourLines(aruco::Marker& marker, cv::Mat cameraMatrix = cv::Mat(),
414  cv::Mat distCoef = cv::Mat());
415 
416  inline float pointSqdist(cv::Point& p, cv::Point2f& p2)
417  {
418  float dx = p.x - p2.x;
419  float dy = p.y - p2.y;
420  return dx * dx + dy * dy;
421  }
422 
423  float _tooNearDistance = -1; // pixel distance between nearr rectangle. Computed
424  // automatically based on the params
425 
426 
427 
429  {
430  void setParams(const std::vector<cv::Point2f>& m)
431  {
432  corners = m;
433  bax = m[1].x - m[0].x;
434  bay = m[1].y - m[0].y;
435  dax = m[2].x - m[0].x;
436  day = m[2].y - m[0].y;
437  a = m[0];
438  b = m[1];
439  d = m[2];
440  area = _getArea();
441 
442  center = cv::Point2f(0, 0);
443  for (auto& p : corners)
444  center += p;
445  center *= 1. / 4.;
446  }
447 
448  bool isInto(const cv::Point2f& p) const
449  {
450  if (signD(corners[0], corners[1], p) < 0)
451  return false;
452  if (signD(corners[1], corners[2], p) < 0)
453  return false;
454  if (signD(corners[2], corners[3], p) < 0)
455  return false;
456  if (signD(corners[3], corners[0], p) < 0)
457  return false;
458  return true;
459  }
460  cv::Point2f getCenter() const
461  {
462  return center;
463  }
464  float getArea() const
465  {
466  return area;
467  }
468  float _getArea() const
469  {
470  // use the cross products
471  cv::Point2f v01 = corners[1] - corners[0];
472  cv::Point2f v03 = corners[3] - corners[0];
473  float area1 = fabs(v01.x * v03.y - v01.y * v03.x);
474  cv::Point2f v21 = corners[1] - corners[2];
475  cv::Point2f v23 = corners[3] - corners[2];
476  float area2 = fabs(v21.x * v23.y - v21.y * v23.x);
477  return (area2 + area1) / 2.f;
478  }
479  float bax, bay, dax, day;
480  cv::Point2f a, b, d;
481  float area;
482  cv::Point2f center;
483 
484  std::vector<cv::Point2f> corners;
485 
486  inline float signD(cv::Point2f p0, cv::Point2f p1, cv::Point2f p) const
487  {
488  return ((p0.y - p1.y) * p.x + (p1.x - p0.x) * p.y + (p0.x * p1.y - p1.x * p0.y)) /
489  sqrt((p1.x - p0.x) * (p1.x - p0.x) + (p1.y - p0.y) * (p1.y - p0.y));
490  }
491  };
492  void addToImageHist(cv::Mat& im, std::vector<float>& hist);
493  int Otsu(std::vector<float>& hist);
494 
495  void filter_ambiguous_query(std::vector<cv::DMatch>& matches);
496  // obfuscate end
497 };
498 }; // namespace aruco
499 #endif
aruco::MarkerDetector_Impl::Queue::mutex_
std::mutex mutex_
Definition: markerdetector_impl.h:409
aruco::MarkerDetector_Impl::ThresAndDetectRectTASK::param2
int param2
Definition: markerdetector_impl.h:370
aruco::MarkerDetector_Impl::getCrossPoint
cv::Point2f getCrossPoint(const cv::Point3f &line1, const cv::Point3f &line2)
Definition: markerdetector_impl.cpp:1532
aruco::MarkerDetector_Impl::marker_analyzer::setParams
void setParams(const std::vector< cv::Point2f > &m)
Definition: markerdetector_impl.h:430
aruco::MarkerDetector_Impl::joinVectors
void joinVectors(std::vector< std::vector< T >> &vv, std::vector< T > &v, bool clearv=false)
Definition: markerdetector_impl.h:313
aruco::MarkerDetector_Impl::saveParamsToFile
void saveParamsToFile(const std::string &path) const
Definition: markerdetector_impl.cpp:1705
aruco::MarkerDetector_Impl::marker_analyzer::center
cv::Point2f center
Definition: markerdetector_impl.h:482
aruco::MarkerDetector_Impl::setDictionary
void setDictionary(std::string dict_type, float error_correction_rate=0)
aruco::MarkerDetector_Impl::getParameters
MarkerDetector::Params getParameters() const
Definition: markerdetector_impl.h:165
aruco::MarkerDetector_Impl::Queue::pop
T pop()
Definition: markerdetector_impl.h:380
aruco::MarkerDetector_Impl::interpolate2Dline
void interpolate2Dline(const std::vector< cv::Point2f > &inPoints, cv::Point3f &outLine)
Definition: markerdetector_impl.cpp:1474
aruco::MarkerDetector_Impl::MarkerDetector_Impl
MarkerDetector_Impl()
Definition: markerdetector_impl.cpp:49
aruco::MarkerDetector_Impl::refineCornerWithContourLines
void refineCornerWithContourLines(aruco::Marker &marker, cv::Mat cameraMatrix=cv::Mat(), cv::Mat distCoef=cv::Mat())
Definition: markerdetector_impl.cpp:1243
aruco::MarkerDetector_Impl::ThresAndDetectRectTASK::outIdx
int outIdx
Definition: markerdetector_impl.h:369
aruco::MarkerDetector_Impl::buildPyramid
void buildPyramid(std::vector< cv::Mat > &imagePyramid, const cv::Mat &grey, int minSize)
Definition: markerdetector_impl.cpp:174
aruco::MarkerDetector_Impl::getImagePyramid
std::vector< cv::Mat > getImagePyramid()
Definition: markerdetector_impl.h:257
aruco::MarkerDetector_Impl::grey
cv::Mat grey
Definition: markerdetector_impl.h:271
aruco::MarkerDetector_Impl::fromStream
void fromStream(std::istream &str)
Definition: markerdetector_impl.cpp:1731
aruco::CameraParameters
Parameters of the camera.
Definition: cameraparameters.h:29
aruco::MarkerDetector_Impl::getParameters
MarkerDetector::Params & getParameters()
Definition: markerdetector_impl.h:171
aruco::MarkerDetector_Impl::setDetectionMode
void setDetectionMode(DetectionMode dm, float minMarkerSize=0)
Definition: markerdetector_impl.cpp:99
aruco::MarkerDetector_Impl::draw
void draw(cv::Mat out, const std::vector< Marker > &markers)
Definition: markerdetector_impl.cpp:1632
aruco::MarkerDetector_Impl::thres
cv::Mat thres
Definition: markerdetector_impl.h:271
aruco::MarkerDetector_Impl::drawAllContours
void drawAllContours(cv::Mat input, std::vector< std::vector< cv::Point >> &contours)
Definition: markerdetector_impl.cpp:1599
aruco::MarkerDetector_Impl::_tasks
Queue< ThresAndDetectRectTASK > _tasks
Definition: markerdetector_impl.h:412
markerdetector.h
aruco::MarkerDetector_Impl::getCandidates
std::vector< MarkerCandidate > getCandidates() const
Definition: markerdetector_impl.h:235
aruco::MarkerDetector_Impl::_candidates_wcontour
std::vector< MarkerCandidate > _candidates_wcontour
Definition: markerdetector_impl.h:347
aruco::MarkerDetector_Impl::marker_analyzer::getCenter
cv::Point2f getCenter() const
Definition: markerdetector_impl.h:460
aruco::MarkerDetector_Impl::Queue
Definition: markerdetector_impl.h:377
aruco::MarkerDetector_Impl::marker_analyzer::isInto
bool isInto(const cv::Point2f &p) const
Definition: markerdetector_impl.h:448
aruco::MarkerDetector_Impl::marker_analyzer::a
cv::Point2f a
Definition: markerdetector_impl.h:480
aruco::MarkerDetector_Impl::getDetectionMode
DetectionMode getDetectionMode()
Definition: markerdetector_impl.cpp:104
aruco::MarkerDetector_Impl::cornerUpsample
void cornerUpsample(std::vector< std::vector< cv::Point2f >> &MarkerCanditates, cv::Size lowResImageSize)
Definition: markerdetector_impl.cpp:1837
aruco::MarkerDetector_Impl::getThresholdedImage
cv::Mat getThresholdedImage(uint32_t idx=0)
Definition: markerdetector_impl.cpp:1673
aruco::MarkerDetector_Impl::pointSqdist
float pointSqdist(cv::Point &p, cv::Point2f &p2)
Definition: markerdetector_impl.h:416
aruco::MarkerDetector_Impl::warp
bool warp(cv::Mat &in, cv::Mat &out, cv::Size size, std::vector< cv::Point2f > points)
Definition: markerdetector_impl.cpp:1433
marker.h
aruco::MarkerDetector_Impl::_prevMarkers
std::vector< Marker > _prevMarkers
Definition: markerdetector_impl.h:348
aruco::MarkerDetector_Impl::marker_analyzer
Definition: markerdetector_impl.h:428
aruco::MarkerDetector_Impl
Main class for marker detection.
Definition: markerdetector_impl.h:41
aruco::MarkerDetector_Impl::~MarkerDetector_Impl
~MarkerDetector_Impl()
Definition: markerdetector_impl.cpp:83
aruco::MarkerDetector_Impl::ENCLOSE_TASK
@ ENCLOSE_TASK
Definition: markerdetector_impl.h:364
aruco::MarkerDetector_Impl::setMarkerLabeler
void setMarkerLabeler(cv::Ptr< MarkerLabeler > detector)
setMakerLabeler sets the labeler employed to analyze the squares and extract the inner binary code
Definition: markerdetector_impl.cpp:1644
aruco::MarkerDetector_Impl::removeElements
void removeElements(std::vector< T > &vinout, const std::vector< bool > &toRemove)
Definition: markerdetector_impl.h:295
aruco::MarkerDetector_Impl::thresholdAndDetectRectangles
std::vector< aruco::MarkerCandidate > thresholdAndDetectRectangles(const cv::Mat &input, int thres_param1, int thres_param2, bool erode, cv::Mat &auxThresImage)
Definition: markerdetector_impl.cpp:422
aruco::MarkerDetector_Impl::marker_analyzer::bay
float bay
Definition: markerdetector_impl.h:479
aruco::MarkerDetector_Impl::imagePyramid
std::vector< cv::Mat > imagePyramid
Definition: markerdetector_impl.h:322
aruco::MarkerDetector_Impl::marker_analyzer::area
float area
Definition: markerdetector_impl.h:481
aruco::MarkerDetector_Impl::filter_ambiguous_query
void filter_ambiguous_query(std::vector< cv::DMatch > &matches)
Definition: markerdetector_impl.cpp:1743
aruco::MarkerDetector_Impl::_tooNearDistance
float _tooNearDistance
Definition: markerdetector_impl.h:423
aruco::MarkerDetector_Impl::getMinMarkerSizePix
int getMinMarkerSizePix(cv::Size orginput_imageSize) const
Definition: markerdetector_impl.cpp:1414
aruco_export.h
aruco::MarkerDetector_Impl::toStream
void toStream(std::ostream &str) const
Definition: markerdetector_impl.cpp:1724
aruco::MarkerDetector_Impl::_vcandidates
std::vector< std::vector< MarkerCandidate > > _vcandidates
Definition: markerdetector_impl.h:345
aruco::MarkerDetector_Impl::marker_analyzer::day
float day
Definition: markerdetector_impl.h:479
aruco::MarkerDetector_Impl::marker_analyzer::d
cv::Point2f d
Definition: markerdetector_impl.h:480
aruco::MarkerDetector_Impl::marker_analyzer::b
cv::Point2f b
Definition: markerdetector_impl.h:480
aruco::MarkerDetector_Impl::prefilterCandidates
std::vector< aruco::MarkerCandidate > prefilterCandidates(std::vector< MarkerCandidate > &candidates, cv::Size orgImageSize)
Definition: markerdetector_impl.cpp:641
aruco::MarkerDetector_Impl::ThresAndDetectRectTASK::param1
int param1
Definition: markerdetector_impl.h:370
aruco::Marker
Definition: marker.h:35
aruco::MarkerDetector_Impl::marker_ndetections
std::map< int, int > marker_ndetections
Definition: markerdetector_impl.h:349
aruco::MarkerDetector_Impl::detect
std::vector< aruco::Marker > detect(const cv::Mat &input)
Definition: markerdetector_impl.cpp:118
aruco::MarkerDetector_Impl::_thres_Images
std::vector< cv::Mat > _thres_Images
Definition: markerdetector_impl.h:344
aruco::MarkerDetector_Impl::marker_analyzer::bax
float bax
Definition: markerdetector_impl.h:479
aruco::MarkerDetector::Params
Definition: markerdetector.h:104
aruco::MarkerDetector_Impl::MarkerCandidate
Marker MarkerCandidate
Definition: markerdetector_impl.h:229
aruco::MarkerDetector_Impl::Queue::push
void push(const T &item)
Definition: markerdetector_impl.h:392
aruco::MarkerDetector_Impl::Queue::size
size_t size()
Definition: markerdetector_impl.h:400
aruco::MarkerDetector_Impl::marker_analyzer::corners
std::vector< cv::Point2f > corners
Definition: markerdetector_impl.h:484
aruco::MarkerDetector_Impl::perimeter
int perimeter(const std::vector< cv::Point2f > &a)
Definition: markerdetector_impl.cpp:1459
aruco::MarkerDetector_Impl::Queue::queue_
std::queue< T > queue_
Definition: markerdetector_impl.h:408
aruco::MarkerDetector_Impl::marker_analyzer::dax
float dax
Definition: markerdetector_impl.h:479
aruco::MarkerDetector_Impl::_params
MarkerDetector::Params _params
Definition: markerdetector_impl.h:268
aruco::MarkerDetector_Impl::marker_analyzer::getArea
float getArea() const
Definition: markerdetector_impl.h:464
aruco::MarkerDetector_Impl::distortPoints
void distortPoints(std::vector< cv::Point2f > in, std::vector< cv::Point2f > &out, const cv::Mat &camMatrix, const cv::Mat &distCoeff)
Definition: markerdetector_impl.cpp:1686
aruco::MarkerDetector
Main class for marker detection.
Definition: markerdetector.h:91
aruco::MarkerDetector_Impl::getMarkerLabeler
cv::Ptr< MarkerLabeler > getMarkerLabeler()
Definition: markerdetector_impl.h:225
aruco::MarkerDetector_Impl::ThreadTasks
ThreadTasks
Definition: markerdetector_impl.h:361
aruco::MarkerDetector_Impl::THRESHOLD_TASK
@ THRESHOLD_TASK
Definition: markerdetector_impl.h:363
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_Impl::markerIdDetector
cv::Ptr< MarkerLabeler > markerIdDetector
Definition: markerdetector_impl.h:273
aruco::MarkerDetector_Impl::EXIT_TASK
@ EXIT_TASK
Definition: markerdetector_impl.h:365
aruco::MarkerDetector_Impl::loadParamsFromFile
void loadParamsFromFile(const std::string &path)
Definition: markerdetector_impl.cpp:1715
aruco::MarkerDetector_Impl::marker_analyzer::_getArea
float _getArea() const
Definition: markerdetector_impl.h:468
aruco::MarkerDetector_Impl::ThresAndDetectRectTASK::task
ThreadTasks task
Definition: markerdetector_impl.h:371
aruco::MarkerDetector_Impl::addToImageHist
void addToImageHist(cv::Mat &im, std::vector< float > &hist)
Definition: markerdetector_impl.cpp:729
aruco::MarkerDetector_Impl::Otsu
int Otsu(std::vector< float > &hist)
Definition: markerdetector_impl.cpp:739
aruco::MarkerDetector_Impl::setParameters
void setParameters(const MarkerDetector::Params &params)
Definition: markerdetector_impl.cpp:87
aruco::MarkerDetector_Impl::drawApproxCurve
void drawApproxCurve(cv::Mat &in, std::vector< cv::Point > &approxCurve, cv::Scalar color, int thickness=1)
Definition: markerdetector_impl.cpp:1618
aruco::MarkerDetector_Impl::ThresAndDetectRectTASK
Definition: markerdetector_impl.h:367
aruco::MarkerDetector_Impl::ThresAndDetectRectTASK::inIdx
int inIdx
Definition: markerdetector_impl.h:369
aruco::MarkerDetector_Impl::enlargeMarkerCandidate
void enlargeMarkerCandidate(MarkerCandidate &cand, int fact=1)
Definition: markerdetector_impl.cpp:1344
aruco::MarkerDetector_Impl::Queue::cond_
std::condition_variable cond_
Definition: markerdetector_impl.h:410
aruco::MarkerDetector_Impl::thresholdAndDetectRectangles_thread
void thresholdAndDetectRectangles_thread()
Definition: markerdetector_impl.cpp:540
aruco::MarkerDetector_Impl::getMarkerWarpSize
int getMarkerWarpSize()
Definition: markerdetector_impl.cpp:159
aruco::MarkerDetector_Impl::marker_analyzer::signD
float signD(cv::Point2f p0, cv::Point2f p1, cv::Point2f p) const
Definition: markerdetector_impl.h:486
aruco::MarkerDetector_Impl::drawContour
void drawContour(cv::Mat &in, std::vector< cv::Point > &contour, cv::Scalar)
Definition: markerdetector_impl.cpp:1610


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