00001
00005 #ifndef CALIBRATION_HPP
00006 #define CALIBRATION_HPP
00007
00008
00009 #include "improc.hpp"
00010
00011
00012
00013
00014
00015
00016
00017
00018 #include "opencv2/calib3d/calib3d.hpp"
00019 #include "opencv2/highgui/highgui.hpp"
00020
00021 #include <sys/stat.h>
00022 #include <stdio.h>
00023
00024 #ifdef _WIN32
00025 #include <ctime>
00026 #endif
00027
00028 #define CHESSBOARD_FINDER_CODE 0
00029 #define MASK_FINDER_CODE 1
00030 #define HEATED_CHESSBOARD_FINDER_CODE 2
00031
00032 #define MIN_CORNER_SEPARATION 3
00033 #define MAX_CORNER_SEPARATION 100
00034
00035 #define ALL_PATTERNS_OPTIMIZATION_CODE 0
00036 #define RANDOM_SET_OPTIMIZATION_CODE 1
00037 #define FIRST_N_PATTERNS_OPTIMIZATION_CODE 2
00038 #define ENHANCED_MCM_OPTIMIZATION_CODE 3
00039 #define BEST_OF_RANDOM_PATTERNS_OPTIMIZATION_CODE 4
00040 #define EXHAUSTIVE_SEARCH_OPTIMIZATION_CODE 5
00041 #define RANDOM_SEED_OPTIMIZATION_CODE 6
00042 #define SCORE_BASED_OPTIMIZATION_CODE 7
00043
00044 #define DEBUG_MODE 0
00045
00046 #define MINIMUM_CORRECTION_DISTANCE 1
00047
00048 #define PATTERN_FINDER_CV_CORNER_SUBPIX_FLAG 4
00049
00050 #define TRACKING 0
00051 #define RADIAL_LENGTH 1000
00052 #define FOLD_COUNT 1
00053
00054 #define PI 3.14159265
00055
00056 #define MAX_CAMS 3
00057 #define MAX_SEARCH_DIST 3
00058
00059 #define REGULAR_OPENCV_CHESSBOARD_FINDER 0
00060 #define MASK_FINDER 3
00061 #define MASK_FINDER_INNERS 8
00062 #define EXTENDED_CHESSBOARD_FINDER 5
00063 #define INVERTED_OPENCV_CHESSBOARD_FINDER 10
00064
00065 #define MIN_DISTANCE_FROM_EDGE 2
00066
00067 #define MAX_FRAMES_PER_INPUT 5000
00068 #define MAX_FRAMES_TO_LOAD 1000
00069 #define MAX_PATTERNS_TO_KEEP 500
00070 #define MAX_CANDIDATE_PATTERNS 100
00071 #define MAX_PATTERNS_PER_SET 10
00072
00073 #define MINIMUM_MSER_AREA 50
00074
00075 #define PATCH_CORRECTION_INTRINSICS_FLAGS CV_CALIB_RATIONAL_MODEL
00076
00077 using namespace std;
00078 using namespace cv;
00079
00081 class mserPatch
00082 {
00083 public:
00085 vector<Point> hull;
00087 Point centroid;
00089 Point2f centroid2f;
00091 Moments momentSet;
00093 double area;
00095 double meanIntensity;
00097 double varIntensity;
00098
00100 mserPatch();
00101
00103 mserPatch(vector<Point>& inputHull, const Mat& image);
00104 };
00105
00107 void generateRandomIndexArray(int * randomArray, int maxElements, int maxVal);
00108
00110 void prepForDisplay(const Mat& distributionMap, Mat& distributionDisplay);
00111
00113 void addToRadialDistribution(double *radialDistribution, cv::vector<Point2f>& cornerSet, Size imSize);
00114
00116 void addToBinMap(Mat& binMap, cv::vector<Point2f>& cornerSet, Size imSize);
00117
00119 double obtainSetScore(Mat& distributionMap,
00120 Mat& binMap,
00121 Mat& gaussianMat,
00122 cv::vector<Point2f>& cornerSet,
00123 double *radialDistribution);
00124
00126 bool verifyCorners(Size imSize, Size patternSize, vector<Point2f>& patternPoints, double minDist = MIN_CORNER_SEPARATION, double maxDist = MAX_CORNER_SEPARATION);
00127
00129 void transferMserElement(vector<vector<Point> >& dst, vector<vector<Point> >& src, int index);
00131 void transferPatchElement(vector<mserPatch>& dst, vector<mserPatch>& src, int index);
00132
00134 void clusterFilter(vector<mserPatch>& patches, vector<vector<Point> >& msers, int totalPatches);
00136 void reduceCluster(vector<mserPatch>& patches, vector<vector<Point> >& msers, int totalPatches);
00137
00139 void enclosureFilter(vector<mserPatch>& patches, vector<vector<Point> >& msers);
00140
00142 void varianceFilter(vector<mserPatch>& patches, vector<vector<Point> >& msers);
00143
00145 void shapeFilter(vector<mserPatch>& patches, vector<vector<Point> >& msers);
00146
00148 void addToDistributionMap(Mat& distributionMap, vector<Point2f>& corners);
00149
00151
00152
00154 bool verifyPattern(Size imSize, Size patternSize, vector<Point2f>& patternPoints, double minDist, double maxDist);
00155
00157 bool findPatternCentres(const Mat& image, Size patternSize, vector<Point2f>& centres, int mode);
00158
00160 void sortPatches(Size imageSize, Size patternSize, vector<Point2f>& patchCentres, int mode);
00161
00163 void reorderPatches(Size patternSize, int mode, int *XVec, int *YVec, vector<Point2f>& patchCentres);
00164
00166 void interpolateCornerLocations2(const Mat& image, int mode, Size patternSize, vector<Point2f>& vCentres, vector<Point2f>& vCorners);
00167
00169 void groupPointsInQuads(Size patternSize, vector<Point2f>& corners);
00170
00172 void refineCornerPositions(const Mat& image, Size patternSize, vector<Point2f>& vCorners);
00173
00175 void initialRefinementOfCorners(const Mat& imGrey, vector<Point2f>& src, Size patternSize);
00176
00178 void sortCorners(Size imageSize, Size patternSize, vector<Point2f>& corners);
00179
00181 int findBestCorners(const Mat& image, vector<Point2f>& src, vector<Point2f>& dst, Size patternSize, int detector, int searchDist = MAX_SEARCH_DIST);
00182
00184 void debugDisplayPattern(const Mat& image, Size patternSize, Mat& corners, bool mode = true, double delay = 0.0);
00185
00187 bool verifyPatches(Size imSize, Size patternSize, vector<Point2f>& patchCentres, int mode, double minDist, double maxDist);
00188
00190 bool correctPatchCentres(const Mat& image, Size patternSize, vector<Point2f>& patchCentres, int mode);
00191
00193 bool findPatchCorners(const Mat& image, Size patternSize, Mat& homography, vector<Point2f>& corners, vector<Point2f>& patchCentres2f, int mode, int detector = 0);
00194
00196 bool findMaskCorners(const Mat& image, Size patternSize, vector<Point2f>& corners, int detector = 0, int mserDelta = 8, float max_var = 0.25, float min_div = 0.2, double area_threshold = 1.01);
00197
00199 bool findPatternCorners(const Mat& image, Size patternSize, vector<Point2f>& corners, int mode, int detector = 0, int mserDelta = 8, float max_var = 0.25, float min_div = 0.2, double area_threshold = 1.01);
00200
00202 void findAllPatches(const Mat& image, Size patternSize, vector<vector<Point> >& msers, int mserDelta = 8, float max_var = 0.25, float min_div = 0.2, double area_threshold = 1.01);
00203
00204
00206 void findEdgePatches(Size patternSize, int mode, int *XVec, int *YVec, vector<Point2f>& patchCentres, vector<Point2f>& remainingPatches);
00207
00209 void findInteriorPatches(Size patternSize, int mode, int *XVec, int *YVec, vector<Point2f>& patchCentres, vector<Point2f>& remainingPatches);
00210
00212 void randomCulling(vector<std::string>& inputList, int maxSearch);
00213
00215 void randomCulling(vector<std::string>& inputList, int maxSearch, vector<vector<Point2f> >& patterns);
00216
00218 void randomCulling(vector<std::string>& inputList, int maxSearch, vector<vector<vector<Point2f> > >& patterns);
00219
00221 bool checkAcutance();
00222
00224 void determineFindablePatches(Size patternSize, int mode, int *XVec, int *YVec);
00225
00227 void findCornerPatches(Size imageSize, Size patternSize, int mode, int *XVec, int *YVec, vector<Point2f>& patchCentres, vector<Point2f>& remainingPatches);
00228
00230 void determinePatchDistribution(Size patternSize, int mode, int& rows, int& cols, int& quant);
00231
00233 void debugDisplayPatches(const Mat& image, vector<vector<Point> >& msers);
00234
00236 bool refinePatches(const Mat& image, Size patternSize, vector<vector<Point> >& msers, vector<Point2f>& patchCentres, int mode);
00237
00239 bool patternInFrame(Size imSize, vector<Point2f>& patternPoints, int minBorder = 2);
00240
00241 #endif