Subversion Repositories seema-scanner

Rev

Rev 140 | Rev 164 | Go to most recent revision | Show entire file | Ignore whitespace | Details | Blame | Last modification | View Log | RSS feed

Rev 140 Rev 148
Line 14... Line 14...
14
    int checkerCountY = settings.value("calibration/checkerCountY", 13).toInt();
14
    int checkerCountY = settings.value("calibration/checkerCountY", 13).toInt();
15
    cv::Size checkerCount(checkerCountX, checkerCountY);
15
    cv::Size checkerCount(checkerCountX, checkerCountY);
16
 
16
 
17
    int nSets = calibrationData.size();
17
    int nSets = calibrationData.size();
18
 
18
 
-
 
19
    // 2D Points collected for OpenCV's calibration procedures
19
    std::vector< std::vector<cv::Point2f> > qc0, qc1;
20
    std::vector< std::vector<cv::Point2f> > qc0, qc1;
20
    std::vector< std::vector<cv::Point2f> > qc0Stereo, qc1Stereo;
21
    std::vector< std::vector<cv::Point2f> > qc0Stereo, qc1Stereo;
21
 
22
 
-
 
23
    std::vector<bool> success0(nSets), success1(nSets);
-
 
24
 
22
    std::vector<float> angles;
25
    std::vector<float> angles;
23
 
26
 
24
    // Loop through calibration sets
27
    // Loop through calibration sets
25
    for(int i=0; i<nSets; i++){
28
    for(int i=0; i<nSets; i++){
26
 
29
 
Line 38... Line 41...
38
            cv::cvtColor(SMCalibrationSetI.frame0, gray, CV_BayerBG2GRAY);
41
            cv::cvtColor(SMCalibrationSetI.frame0, gray, CV_BayerBG2GRAY);
39
        else
42
        else
40
            cv::cvtColor(SMCalibrationSetI.frame0, gray, CV_RGB2GRAY);
43
            cv::cvtColor(SMCalibrationSetI.frame0, gray, CV_RGB2GRAY);
41
 
44
 
42
        // Extract checker corners
45
        // Extract checker corners
43
        bool success0 = cv::findChessboardCorners(gray, checkerCount, qci0, cv::CALIB_CB_ADAPTIVE_THRESH + cv::CALIB_CB_FAST_CHECK);
46
        success0[i] = cv::findChessboardCorners(gray, checkerCount, qci0, cv::CALIB_CB_ADAPTIVE_THRESH + cv::CALIB_CB_FAST_CHECK);
44
        if(success0){
47
        if(success0[i]){
45
            cv::cornerSubPix(gray, qci0, cv::Size(6, 6), cv::Size(1, 1),cv::TermCriteria(CV_TERMCRIT_EPS + CV_TERMCRIT_ITER, 20, 0.0001));
48
            cv::cornerSubPix(gray, qci0, cv::Size(6, 6), cv::Size(1, 1),cv::TermCriteria(CV_TERMCRIT_EPS + CV_TERMCRIT_ITER, 20, 0.0001));
46
            // Draw colored chessboard
49
            // Draw colored chessboard
47
            cv::Mat color;
50
            cv::Mat color;
48
            if(SMCalibrationSetI.frame0.channels() == 1)
51
            if(SMCalibrationSetI.frame0.channels() == 1)
49
                cv::cvtColor(SMCalibrationSetI.frame0, color, CV_BayerBG2RGB);
52
                cv::cvtColor(SMCalibrationSetI.frame0, color, CV_BayerBG2RGB);
50
            else
53
            else
51
                color = SMCalibrationSetI.frame0.clone();
54
                color = SMCalibrationSetI.frame0.clone();
52
 
55
 
53
            cvtools::drawChessboardCorners(color, checkerCount, qci0, success0, 10);
56
            cvtools::drawChessboardCorners(color, checkerCount, qci0, success0[i], 10);
54
            SMCalibrationSetI.frame0Result = color;
57
            SMCalibrationSetI.frame0Result = color;
55
        }
58
        }
56
 
59
 
57
        emit newFrameResult(i, 0, success0, SMCalibrationSetI.frame0Result);
60
        emit newFrameResult(i, 0, success0[i], SMCalibrationSetI.frame0Result);
58
 
61
 
59
        // Camera 1
62
        // Camera 1
60
        std::vector<cv::Point2f> qci1;
63
        std::vector<cv::Point2f> qci1;
61
 
64
 
62
        // Convert to grayscale
65
        // Convert to grayscale
Line 64... Line 67...
64
            cv::cvtColor(SMCalibrationSetI.frame1, gray, CV_BayerBG2GRAY);
67
            cv::cvtColor(SMCalibrationSetI.frame1, gray, CV_BayerBG2GRAY);
65
        else
68
        else
66
            cv::cvtColor(SMCalibrationSetI.frame1, gray, CV_RGB2GRAY);
69
            cv::cvtColor(SMCalibrationSetI.frame1, gray, CV_RGB2GRAY);
67
 
70
 
68
        // Extract checker corners
71
        // Extract checker corners
69
        bool success1 = cv::findChessboardCorners(gray, checkerCount, qci1, cv::CALIB_CB_ADAPTIVE_THRESH + cv::CALIB_CB_FAST_CHECK);
72
        success1[i] = cv::findChessboardCorners(gray, checkerCount, qci1, cv::CALIB_CB_ADAPTIVE_THRESH + cv::CALIB_CB_FAST_CHECK);
70
        if(success1){
73
        if(success1[i]){
71
            cv::cornerSubPix(gray, qci1, cv::Size(6, 6), cv::Size(1, 1),cv::TermCriteria(CV_TERMCRIT_EPS + CV_TERMCRIT_ITER, 20, 0.0001));
74
            cv::cornerSubPix(gray, qci1, cv::Size(6, 6), cv::Size(1, 1),cv::TermCriteria(CV_TERMCRIT_EPS + CV_TERMCRIT_ITER, 20, 0.0001));
72
            // Draw colored chessboard
75
            // Draw colored chessboard
73
            cv::Mat color;
76
            cv::Mat color;
74
            if(SMCalibrationSetI.frame1.channels() == 1)
77
            if(SMCalibrationSetI.frame1.channels() == 1)
75
                cv::cvtColor(SMCalibrationSetI.frame1, color, CV_BayerBG2RGB);
78
                cv::cvtColor(SMCalibrationSetI.frame1, color, CV_BayerBG2RGB);
76
            else
79
            else
77
                color = SMCalibrationSetI.frame1.clone();
80
                color = SMCalibrationSetI.frame1.clone();
78
 
81
 
79
            cvtools::drawChessboardCorners(color, checkerCount, qci1, success1, 10);
82
            cvtools::drawChessboardCorners(color, checkerCount, qci1, success1[i], 10);
80
            SMCalibrationSetI.frame1Result = color;
83
            SMCalibrationSetI.frame1Result = color;
81
        }
84
        }
82
 
85
 
83
        emit newFrameResult(i, 1, success1, SMCalibrationSetI.frame1Result);
86
        emit newFrameResult(i, 1, success1[i], SMCalibrationSetI.frame1Result);
84
 
87
 
85
        if(success0)
88
        if(success0[i])
86
            qc0.push_back(qci0);
89
            qc0.push_back(qci0);
87
 
90
 
88
        if(success1)
91
        if(success1[i])
89
            qc1.push_back(qci1);
92
            qc1.push_back(qci1);
90
 
93
 
91
        if(success0 && success1){
94
        if(success0[i] && success1[i]){
92
            qc0Stereo.push_back(qci0);
95
            qc0Stereo.push_back(qci0);
93
            qc1Stereo.push_back(qci1);
96
            qc1Stereo.push_back(qci1);
94
            angles.push_back(SMCalibrationSetI.rotationAngle);
97
            angles.push_back(SMCalibrationSetI.rotationAngle);
95
        }
98
        }
96
 
99
 
Line 152... Line 155...
152
    cal.R1 = R1;
155
    cal.R1 = R1;
153
    cal.T1 = T1;
156
    cal.T1 = T1;
154
    cal.E = E;
157
    cal.E = E;
155
    cal.F = F;
158
    cal.F = F;
156
 
159
 
-
 
160
    // Determine per-view reprojection errors:
-
 
161
    cal.cam0_errors_per_view.resize(nSets);
-
 
162
    int idx = 0;
-
 
163
    for(unsigned int i = 0; i < nSets; ++i){
-
 
164
        if(success0[i]){
-
 
165
            int n = (int)Q0[idx].size();
-
 
166
            std::vector<cv::Point2f> qc_proj;
-
 
167
            cv::projectPoints(cv::Mat(Q0[idx]), cam_rvecs0[idx], cam_tvecs0[idx], cal.K0,  cal.k0, qc_proj);
-
 
168
            float err = 0;
-
 
169
            for(int j=0; j<qc_proj.size(); j++){
-
 
170
                cv::Point2f d = qc0[idx][j] - qc_proj[j];
-
 
171
                err += cv::sqrt(d.x*d.x + d.y*d.y);
-
 
172
            }
-
 
173
            cal.cam0_errors_per_view[i] = (float)err/n;
-
 
174
            idx++;
-
 
175
        } else
-
 
176
            cal.cam0_errors_per_view[i] = NAN;
-
 
177
    }
-
 
178
    cal.cam1_errors_per_view.resize(nSets);
-
 
179
    idx = 0;
-
 
180
    for(unsigned int i = 0; i < nSets; ++i){
-
 
181
        if(success1[i]){
-
 
182
            int n = (int)Q1[idx].size();
-
 
183
            std::vector<cv::Point2f> qc_proj;
-
 
184
            cv::projectPoints(cv::Mat(Q1[idx]), cam_rvecs1[idx], cam_tvecs1[idx], cal.K1,  cal.k1, qc_proj);
-
 
185
            float err = 0;
-
 
186
            for(int j=0; j<qc_proj.size(); j++){
-
 
187
                cv::Point2f d = qc1[idx][j] - qc_proj[j];
-
 
188
                err += cv::sqrt(d.x*d.x + d.y*d.y);
-
 
189
            }
-
 
190
            cal.cam1_errors_per_view[i] = (float)err/n;
-
 
191
            idx++;
-
 
192
       } else
-
 
193
            cal.cam1_errors_per_view[i] = NAN;
-
 
194
    }
-
 
195
 
157
//    // hand-eye calibration
196
//    // hand-eye calibration
158
//    std::vector<cv::Matx33f> Rc(nValidSets - 1); // rotations/translations of the checkerboard in camera 0 reference frame
197
//    std::vector<cv::Matx33f> Rc(nValidSets - 1); // rotations/translations of the checkerboard in camera 0 reference frame
159
//    std::vector<cv::Vec3f> Tc(nValidSets - 1);
198
//    std::vector<cv::Vec3f> Tc(nValidSets - 1);
160
//    std::vector<cv::Matx33f> Rr(nValidSets - 1); // in rotation stage reference frame
199
//    std::vector<cv::Matx33f> Rr(nValidSets - 1); // in rotation stage reference frame
161
//    std::vector<cv::Vec3f> Tr(nValidSets - 1);
200
//    std::vector<cv::Vec3f> Tr(nValidSets - 1);