Go to the documentation of this file.00001
00002
00003
00004
00005
00006
00007
00008
00009
00010
00011
00012
00013
00014
00015
00016
00017
00018
00019
00020
00021
00022
00023
00024
00025
00026
00027
00028
00029 #ifndef CHROMATICMASK_H
00030 #define CHROMATICMASK_H
00031
00032 #include <opencv2/core/core.hpp>
00033 #include <opencv2/ml/ml.hpp>
00034 #include <opencv2/calib3d/calib3d.hpp>
00035 #include <opencv2/highgui/highgui.hpp>
00036 #include <opencv2/imgproc/imgproc.hpp>
00037 #include <opencv2/ml/ml.hpp>
00038 #include "exports.h"
00039 #include "board.h"
00040 #include "boarddetector.h"
00041 #include "cvdrawingutils.h"
00042
00043
00044 class ARUCO_EXPORTS EMClassifier {
00045 public:
00046 EMClassifier(unsigned int nelements = 200);
00047 void addSample(uchar s) { _samples.push_back(s); };
00048 void clearSamples() { _samples.clear(); };
00049 void train();
00050 bool classify(uchar s) { return _inside[s]; };
00051 double getProb(uchar s) { return _prob[s]; };
00052 unsigned int numsamples() { return _samples.size(); };
00053 void setProb(double p) { _threshProb = p; }
00054
00055
00056
00057 private:
00058 #ifdef OPENCV_VERSION_3
00059 cv::Ptr< cv::ml::EM > _classifier;
00060 #else
00061 cv::EM _classifier;
00062 #endif
00063 vector< uchar > _samples;
00064 bool _inside[256];
00065 double _prob[256];
00066 double _histogram[256];
00067 unsigned int _nelem;
00068 double _threshProb;
00069 };
00070
00071
00072 class ARUCO_EXPORTS ChromaticMask {
00073 public:
00074 ChromaticMask() : _cellSize(20) { _isValid = false; };
00075
00076 void setParams(unsigned int mc, unsigned int nc, double threshProb, aruco::CameraParameters CP, aruco::BoardConfiguration BC,
00077 vector< cv::Point3f > corners);
00078 void setParams(unsigned int mc, unsigned int nc, double threshProb, aruco::CameraParameters CP, aruco::BoardConfiguration BC, float markersize = -1.);
00079
00080 void calculateGridImage(const aruco::Board &board);
00081
00082 cv::Mat getCellMap() { return _cellMap; };
00083 cv::Mat getMask() { return _mask; };
00084
00085 void train(const cv::Mat &in, const aruco::Board &board);
00086 void classify(const cv::Mat &in, const aruco::Board &board);
00087 void classify2(const cv::Mat &in, const aruco::Board &board);
00088 void update(const cv::Mat &in);
00089
00090 bool isValid() { return _isValid; };
00091 void resetMask();
00092
00093 private:
00094 double getDistance(cv::Point2d pixel, unsigned int classifier) {
00095 cv::Vec2b canPos = _canonicalPos.at< cv::Vec2b >(pixel.y, pixel.x)[0];
00096 return norm(_cellCenters[classifier] - cv::Point2f(canPos[0], canPos[1]));
00097 }
00098
00099 vector< cv::Point2f > _imgCornerPoints;
00100 vector< cv::Point3f > _objCornerPoints;
00101 cv::Mat _perpTrans;
00102 vector< EMClassifier > _classifiers;
00103 vector< cv::Point2f > _centers;
00104 vector< cv::Point2f > _pixelsVector;
00105 vector< cv::Point2f > _cellCenters;
00106 vector< vector< size_t > > _cell_neighbours;
00107 const float _cellSize;
00108
00109
00110 unsigned int _mc, _nc;
00111 aruco::BoardDetector _BD;
00112 aruco::CameraParameters _CP;
00113 cv::Mat _canonicalPos, _cellMap, _mask, _maskAux;
00114 bool _isValid;
00115 double _threshProb;
00116 };
00117
00118 #endif // CHROMATICMASK_H