17 #ifndef _ARUCO_MarkerDetector_Impl_H
18 #define _ARUCO_MarkerDetector_Impl_H
21 #include <opencv2/core/core.hpp>
26 #include <condition_variable>
31 #include <opencv2/imgproc/imgproc.hpp>
36 class CameraParameters;
115 std::vector<aruco::Marker>
detect(
const cv::Mat& input);
117 float markerSizeMeters,
bool setYPerperdicular =
false,
118 bool correctFisheye =
false);
133 void detect(
const cv::Mat& input, std::vector<Marker>& detectedMarkers,
135 bool setYPerperdicular =
false,
bool correctFisheye =
false);
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);
190 void setDictionary(std::string dict_type,
float error_correction_rate = 0);
201 void setDictionary(
int dict_type,
float error_correction_rate = 0);
248 bool warp(cv::Mat& in, cv::Mat& out, cv::Size size, std::vector<cv::Point2f> points);
252 void toStream(std::ostream& str)
const;
276 int perimeter(
const std::vector<cv::Point2f>& a);
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);
294 template <
typename T>
298 size_t indexValid = 0;
299 for (
size_t i = 0; i < toRemove.size(); i++)
304 vinout[indexValid] = vinout[i];
308 vinout.resize(indexValid);
312 template <
typename T>
313 void joinVectors(std::vector<std::vector<T>>& vv, std::vector<T>& v,
bool clearv =
false)
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]);
325 void cornerUpsample(std::vector<std::vector<cv::Point2f>>& MarkerCanditates,
326 cv::Size lowResImageSize);
327 void cornerUpsample(std::vector<Marker>& MarkerCanditates, cv::Size lowResImageSize);
337 int thres_param2,
bool erode,
338 cv::Mat& auxThresImage);
340 std::vector<aruco::MarkerCandidate>
prefilterCandidates(std::vector<MarkerCandidate>& candidates,
341 cv::Size orgImageSize);
353 void drawApproxCurve(cv::Mat& in, std::vector<cv::Point>& approxCurve, cv::Scalar color,
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);
376 template <
typename T>
382 std::unique_lock<std::mutex> mlock(
mutex_);
387 auto item =
queue_.front();
394 std::unique_lock<std::mutex> mlock(
mutex_);
402 std::unique_lock<std::mutex> mlock(
mutex_);
414 cv::Mat distCoef = cv::Mat());
418 float dx = p.x - p2.x;
419 float dy = p.y - p2.y;
420 return dx * dx + dy * dy;
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;
442 center = cv::Point2f(0, 0);
473 float area1 = fabs(v01.x * v03.y - v01.y * v03.x);
476 float area2 = fabs(v21.x * v23.y - v21.y * v23.x);
477 return (area2 + area1) / 2.f;
486 inline float signD(cv::Point2f p0, cv::Point2f p1, cv::Point2f p)
const
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));
493 int Otsu(std::vector<float>& hist);