$search
00001 00005 #ifndef CALIBRATION_HPP 00006 #define CALIBRATION_HPP 00007 00008 //#include "cv_utils.hpp" 00009 #include "improc.hpp" 00010 00011 // ============================================= 00012 // INCLUDES 00013 // ============================================= 00014 00015 //#include "cv_utils.hpp" 00016 //#include "im_proc.hpp" 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 ALL_PATTERNS_OPTIMIZATION_CODE 0 00033 #define RANDOM_SET_OPTIMIZATION_CODE 1 00034 #define FIRST_N_PATTERNS_OPTIMIZATION_CODE 2 00035 #define ENHANCED_MCM_OPTIMIZATION_CODE 3 00036 #define BEST_OF_RANDOM_PATTERNS_OPTIMIZATION_CODE 4 00037 #define EXHAUSTIVE_SEARCH_OPTIMIZATION_CODE 5 00038 #define RANDOM_SEED_OPTIMIZATION_CODE 6 00039 #define SCORE_BASED_OPTIMIZATION_CODE 7 00040 00041 #define DEBUG_MODE 0 00042 00043 #define PATTERN_FINDER_CV_CORNER_SUBPIX_FLAG 4 00044 00045 #define TRACKING 0 00046 #define RADIAL_LENGTH 1000 00047 #define FOLD_COUNT 1 00048 00049 #define PI 3.14159265 00050 00051 #define MAX_CAMS 3 00052 #define MAX_SEARCH_DIST 3 00053 00054 #define REGULAR_OPENCV_CHESSBOARD_FINDER 0 00055 #define MASK_FINDER 3 00056 #define MASK_FINDER_INNERS 8 00057 #define EXTENDED_CHESSBOARD_FINDER 5 00058 #define INVERTED_OPENCV_CHESSBOARD_FINDER 10 00059 00060 #define MIN_DISTANCE_FROM_EDGE 2 00061 00062 #define MAX_FRAMES_PER_INPUT 5000 00063 #define MAX_FRAMES_TO_LOAD 1000 00064 #define MAX_PATTERNS_TO_KEEP 500 00065 #define MAX_CANDIDATE_PATTERNS 100 00066 #define MAX_PATTERNS_PER_SET 10 00067 00068 #define PATCH_CORRECTION_INTRINSICS_FLAGS CV_CALIB_RATIONAL_MODEL 00069 00070 using namespace std; 00071 using namespace cv; 00072 00074 class mserPatch 00075 { 00076 public: 00078 vector<Point> hull; 00080 Point centroid; 00082 Point2f centroid2f; 00084 Moments momentSet; 00086 double area; 00088 double meanIntensity; 00090 double varIntensity; 00091 00093 mserPatch(); 00094 00096 mserPatch(vector<Point>& inputHull, const Mat& image); 00097 }; 00098 00100 void generateRandomIndexArray(int * randomArray, int maxElements, int maxVal); 00101 00103 void prepForDisplay(const Mat& distributionMap, Mat& distributionDisplay); 00104 00106 void addToRadialDistribution(double *radialDistribution, cv::vector<Point2f>& cornerSet, Size imSize); 00107 00109 void addToBinMap(Mat& binMap, cv::vector<Point2f>& cornerSet, Size imSize); 00110 00112 double obtainSetScore(Mat& distributionMap, 00113 Mat& binMap, 00114 Mat& gaussianMat, 00115 cv::vector<Point2f>& cornerSet, 00116 double *radialDistribution); 00117 00119 bool verifyCorners(Size imSize, Size patternSize, vector<Point2f>& patternPoints, double minDist, double maxDist); 00120 00122 void transferMserElement(vector<vector<Point> >& dst, vector<vector<Point> >& src, int index); 00124 void transferPatchElement(vector<mserPatch>& dst, vector<mserPatch>& src, int index); 00125 00127 void clusterFilter(vector<mserPatch>& patches, vector<vector<Point> >& msers, int totalPatches); 00129 void reduceCluster(vector<mserPatch>& patches, vector<vector<Point> >& msers, int totalPatches); 00130 00132 void enclosureFilter(vector<mserPatch>& patches, vector<vector<Point> >& msers); 00133 00135 void varianceFilter(vector<mserPatch>& patches, vector<vector<Point> >& msers); 00136 00138 void shapeFilter(vector<mserPatch>& patches, vector<vector<Point> >& msers); 00139 00141 void addToDistributionMap(Mat& distributionMap, vector<Point2f>& corners); 00142 00144 //void redistortPoints(const vector<Point2f>& src, vector<Point2f>& dst, const Mat& cameraMatrix, const Mat& distCoeffs, const Mat& newCamMat=Mat::eye(3,3,CV_64FC1)); 00145 00147 bool verifyPattern(Size imSize, Size patternSize, vector<Point2f>& patternPoints, double minDist, double maxDist); 00148 00150 bool findPatternCentres(const Mat& image, Size patternSize, vector<Point2f>& centres, int mode); 00151 00153 void sortPatches(Size imageSize, Size patternSize, vector<Point2f>& patchCentres, int mode); 00154 00156 void reorderPatches(Size patternSize, int mode, int *XVec, int *YVec, vector<Point2f>& patchCentres); 00157 00159 void interpolateCornerLocations2(const Mat& image, int mode, Size patternSize, vector<Point2f>& vCentres, vector<Point2f>& vCorners); 00160 00162 void groupPointsInQuads(Size patternSize, vector<Point2f>& corners); 00163 00165 void refineCornerPositions(const Mat& image, Size patternSize, vector<Point2f>& vCorners); 00166 00168 void initialRefinementOfCorners(const Mat& imGrey, vector<Point2f>& src, Size patternSize); 00169 00171 void sortCorners(Size imageSize, Size patternSize, vector<Point2f>& corners); 00172 00174 int findBestCorners(const Mat& image, vector<Point2f>& src, vector<Point2f>& dst, Size patternSize, int detector, int searchDist = MAX_SEARCH_DIST); 00175 00177 void debugDisplayPattern(const Mat& image, Size patternSize, Mat& corners, bool mode = true); 00178 00180 bool verifyPatches(Size imSize, Size patternSize, vector<Point2f>& patchCentres, int mode, double minDist, double maxDist); 00181 00183 bool correctPatchCentres(const Mat& image, Size patternSize, vector<Point2f>& patchCentres, int mode); 00184 00186 bool findPatchCorners(const Mat& image, Size patternSize, Mat& homography, vector<Point2f>& corners, vector<Point2f>& patchCentres2f, int mode, int detector = 0); 00187 00189 bool findMaskCorners_1(const Mat& image, Size patternSize, vector<Point2f>& corners, int detector = 0); 00190 00191 //HGH 00192 bool findMaskCorners_2(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); 00193 00195 bool findPatternCorners(const Mat& image, Size patternSize, vector<Point2f>& corners, int mode, int detector = 0); 00196 00197 //HGH 00198 bool findPatternCorners2(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); 00199 00201 void findAllPatches(const Mat& image, Size patternSize, vector<vector<Point> >& msers); 00202 00203 //HGH 00204 void findAllPatches2(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); 00205 00207 void findEdgePatches(Size patternSize, int mode, int *XVec, int *YVec, vector<Point2f>& patchCentres, vector<Point2f>& remainingPatches); 00208 00210 void findInteriorPatches(Size patternSize, int mode, int *XVec, int *YVec, vector<Point2f>& patchCentres, vector<Point2f>& remainingPatches); 00211 00213 void randomCulling(vector<std::string>& inputList, int maxSearch); 00214 00216 void randomCulling(vector<std::string>& inputList, int maxSearch, vector<vector<Point2f> >& patterns); 00217 00219 void randomCulling(vector<std::string>& inputList, int maxSearch, vector<vector<vector<Point2f> > >& patterns); 00220 00222 bool checkAcutance(); 00223 00225 void determineFindablePatches(Size patternSize, int mode, int *XVec, int *YVec); 00226 00228 void findCornerPatches(Size imageSize, Size patternSize, int mode, int *XVec, int *YVec, vector<Point2f>& patchCentres, vector<Point2f>& remainingPatches); 00229 00231 void determinePatchDistribution(Size patternSize, int mode, int& rows, int& cols, int& quant); 00232 00234 void debugDisplayPatches(const Mat& image, vector<vector<Point> >& msers); 00235 00237 bool refinePatches(const Mat& image, Size patternSize, vector<vector<Point> >& msers, vector<Point2f>& patchCentres, int mode); 00238 00240 bool patternInFrame(Size imSize, vector<Point2f>& patternPoints, int minBorder = 2); 00241 00242 #endif