Subversion Repositories seema-scanner

Rev

Rev 113 | Rev 121 | Go to most recent revision | Details | Compare with Previous | Last modification | View Log | RSS feed

Rev Author Line No. Line
27 jakw 1
#include "SMCalibrationWorker.h"
2
#include "SMCalibrationParameters.h"
22 jakw 3
 
31 jakw 4
#include "cvtools.h"
5
 
22 jakw 6
#include <QSettings>
7
 
27 jakw 8
void SMCalibrationWorker::performCalibration(std::vector<SMCalibrationSet> calibrationData){
22 jakw 9
 
33 jakw 10
    QSettings settings;
11
 
22 jakw 12
    // Number of saddle points on calibration pattern
80 jakw 13
    int checkerCountX = settings.value("calibration/checkerCountX", 22).toInt();
14
    int checkerCountY = settings.value("calibration/checkerCountY", 13).toInt();
33 jakw 15
    cv::Size checkerCount(checkerCountX, checkerCountY);
22 jakw 16
 
25 jakw 17
    int nSets = calibrationData.size();
22 jakw 18
 
31 jakw 19
    std::vector< std::vector<cv::Point2f> > qc0, qc1;
20
    std::vector<float> angles;
22 jakw 21
 
22
    // Loop through calibration sets
23
    for(int i=0; i<nSets; i++){
24
 
27 jakw 25
        SMCalibrationSet SMCalibrationSetI = calibrationData[i];
25 jakw 26
 
27 jakw 27
        if(!SMCalibrationSetI.checked)
22 jakw 28
            continue;
25 jakw 29
 
30
        // Camera 0
31
        std::vector<cv::Point2f> qci0;
32
        // Extract checker corners
79 jakw 33
        bool success0 = cv::findChessboardCorners(SMCalibrationSetI.frame0, checkerCount, qci0, cv::CALIB_CB_ADAPTIVE_THRESH + cv::CALIB_CB_FAST_CHECK);
25 jakw 34
        if(success0){
113 jakw 35
            // Convert bayer to grayscale
26 jakw 36
            cv::Mat gray;
113 jakw 37
            cv::cvtColor(SMCalibrationSetI.frame0, gray, CV_BayerBG2GRAY);
27 jakw 38
            cv::cornerSubPix(gray, qci0, cv::Size(5, 5), cv::Size(-1, -1),cv::TermCriteria(CV_TERMCRIT_EPS + CV_TERMCRIT_ITER, 20, 0.001));
25 jakw 39
            // Draw colored chessboard
27 jakw 40
            SMCalibrationSetI.frame0Result = SMCalibrationSetI.frame0.clone();
50 jakw 41
            cvtools::drawChessboardCorners(SMCalibrationSetI.frame0Result, checkerCount, qci0, success0, 10);
22 jakw 42
        }
43
 
29 jakw 44
        emit newFrameResult(i, 0, success0, SMCalibrationSetI.frame0Result);
45
 
25 jakw 46
        // Camera 1
47
        std::vector<cv::Point2f> qci1;
48
        // Extract checker corners
79 jakw 49
        bool success1 = cv::findChessboardCorners(SMCalibrationSetI.frame1, checkerCount, qci1, cv::CALIB_CB_ADAPTIVE_THRESH + cv::CALIB_CB_FAST_CHECK);
25 jakw 50
        if(success1){
113 jakw 51
            // Convert bayer to grayscale
26 jakw 52
            cv::Mat gray;
113 jakw 53
            cv::cvtColor(SMCalibrationSetI.frame1, gray, CV_BayerBG2GRAY);
27 jakw 54
            cv::cornerSubPix(gray, qci1, cv::Size(5, 5), cv::Size(-1, -1),cv::TermCriteria(CV_TERMCRIT_EPS + CV_TERMCRIT_ITER, 20, 0.001));
25 jakw 55
            // Draw colored chessboard
27 jakw 56
            SMCalibrationSetI.frame1Result = SMCalibrationSetI.frame1.clone();
50 jakw 57
            cvtools::drawChessboardCorners(SMCalibrationSetI.frame1Result, checkerCount, qci1, success1, 10);
22 jakw 58
        }
59
 
29 jakw 60
        emit newFrameResult(i, 1, success1, SMCalibrationSetI.frame1Result);
61
 
27 jakw 62
        SMCalibrationSetI.success = success0 && success1;
25 jakw 63
 
22 jakw 64
        // Add to whole set
27 jakw 65
        if(SMCalibrationSetI.success){
31 jakw 66
            qc0.push_back(qci0);
67
            qc1.push_back(qci1);
68
            angles.push_back(SMCalibrationSetI.rotationAngle);
22 jakw 69
        }
70
 
27 jakw 71
        // Show progress
72
        emit newSetProcessed(i);
22 jakw 73
    }
74
 
31 jakw 75
    int nValidSets = qc0.size();
27 jakw 76
    if(nValidSets < 2){
22 jakw 77
        std::cerr << "Not enough valid calibration sequences!" << std::endl;
29 jakw 78
        emit done();
22 jakw 79
        return;
80
    }
81
 
82
    // Generate world object coordinates [mm]
33 jakw 83
    float checkerSize = settings.value("calibration/checkerSize", 15.0).toFloat(); // width and height of one field in mm
22 jakw 84
    std::vector<cv::Point3f> Qi;
33 jakw 85
    for (int h=0; h<checkerCount.height; h++)
86
        for (int w=0; w<checkerCount.width; w++)
87
            Qi.push_back(cv::Point3f(checkerSize * w, checkerSize* h, 0.0));
22 jakw 88
    std::vector< std::vector<cv::Point3f> > Q;
31 jakw 89
    for(int i=0; i<qc0.size(); i++)
22 jakw 90
        Q.push_back(Qi);
91
 
92
    // calibrate the cameras
31 jakw 93
    SMCalibrationParameters cal;
94
    cal.frameWidth = calibrationData[0].frame0.cols;
95
    cal.frameHeight = calibrationData[0].frame0.rows;
96
    cv::Size frameSize(cal.frameWidth, cal.frameHeight);
22 jakw 97
 
68 jakw 98
    // determine only k1, k2 for lens distortion
86 jakw 99
    int flags = cv::CALIB_FIX_K3;
33 jakw 100
    // Note: several of the output arguments below must be cv::Mat, otherwise segfault
101
    std::vector<cv::Mat> cam_rvecs0, cam_tvecs0;
31 jakw 102
    cal.cam0_error = cv::calibrateCamera(Q, qc0, frameSize, cal.K0, cal.k0, cam_rvecs0, cam_tvecs0, flags);
27 jakw 103
 
86 jakw 104
    // refine extrinsics for camera 0
105
    for(int i=0; i<Q.size(); i++)
106
        cv::solvePnPRansac(Q[i], qc0[i], cal.K0, cal.k0, cam_rvecs0[i], cam_tvecs0[i], true, 100, 0.05, 100, cv::noArray(), CV_ITERATIVE);
107
 
33 jakw 108
    std::vector<cv::Mat> cam_rvecs1, cam_tvecs1;
31 jakw 109
    cal.cam1_error = cv::calibrateCamera(Q, qc1, frameSize, cal.K1, cal.k1, cam_rvecs1, cam_tvecs1, flags);
22 jakw 110
 
111 jakw 111
    // stereo calibration
112
    int flags_stereo = cv::CALIB_USE_INTRINSIC_GUESS + cv::CALIB_FIX_K3;
33 jakw 113
    cv::Mat E, F, R1, T1;
31 jakw 114
    cal.stereo_error = cv::stereoCalibrate(Q, qc0, qc1, cal.K0, cal.k0, cal.K1, cal.k1,
33 jakw 115
                                              frameSize, R1, T1, E, F,
22 jakw 116
                                              cv::TermCriteria(cv::TermCriteria::COUNT + cv::TermCriteria::EPS, 50, DBL_EPSILON),
117
                                              flags_stereo);
118
 
33 jakw 119
    cal.R1 = R1;
120
    cal.T1 = T1;
121
    cal.E = E;
122
    cal.F = F;
123
 
91 jakw 124
//    // hand-eye calibration
125
//    std::vector<cv::Matx33f> Rc(nValidSets - 1); // rotations/translations of the checkerboard in camera 0 reference frame
126
//    std::vector<cv::Vec3f> Tc(nValidSets - 1);
127
//    std::vector<cv::Matx33f> Rr(nValidSets - 1); // in rotation stage reference frame
128
//    std::vector<cv::Vec3f> Tr(nValidSets - 1);
129
//    for(int i=0; i<nValidSets-1; i++){
130
//        // relative transformations in camera
131
//        cv::Mat cRw1, cRw2;
132
//        cv::Rodrigues(cam_rvecs0[i], cRw1);
133
//        cv::Rodrigues(cam_rvecs0[i+1], cRw2);
134
//        cv::Mat cTw1 = cam_tvecs0[i];
135
//        cv::Mat cTw2 = cam_tvecs0[i+1];
136
//        cv::Mat w1Rc = cRw1.t();
137
//        cv::Mat w1Tc = -cRw1.t()*cTw1;
138
//        Rc[i] = cv::Mat(cRw2*w1Rc);
139
//        Tc[i] = cv::Mat(cRw2*w1Tc+cTw2);
31 jakw 140
 
91 jakw 141
//        // relative transformations in rotation stage
142
//        // we define the rotation axis to be in origo, pointing in positive y direction
143
//        float angleRadians = (angles[i+1]-angles[i])/180.0*M_PI;
144
//        cv::Vec3f rot_rvec(0.0, -angleRadians, 0.0);
145
//        cv::Mat Rri;
146
//        cv::Rodrigues(rot_rvec, Rri);
147
//        Rr[i] = Rri;
148
//        Tr[i] = 0.0;
33 jakw 149
 
91 jakw 150
////        std::cout << i << std::endl;
151
////        std::cout << "cTw1" << cTw1 << std::endl;
152
////        std::cout << "cTw2" << cTw2 << std::endl;
153
////        std::cout << "w2Rc" << w2Rc << std::endl;
154
////        std::cout << "w2Tc" << w2Tc << std::endl;
155
 
156
////        std::cout << "w2Rc" << w2Rc << std::endl;
157
////        std::cout << "w2Tc" << w2Tc << std::endl;
158
 
159
////        cv::Mat Rci;
160
////        cv::Rodrigues(Rc[i], Rci);
161
////        std::cout << "Rci" << Rci << std::endl;
162
////        std::cout << "Tc[i]" << Tc[i] << std::endl;
163
 
164
////        std::cout << "rot_rvec" << rot_rvec << std::endl;
165
////        std::cout << "Tr[i]" << Tr[i] << std::endl;
166
////        std::cout << std::endl;
167
//    }
168
 
169
//    // determine the transformation from rotation stage to camera 0
170
//    cvtools::handEyeCalibrationTsai(Rc, Tc, Rr, Tr, cal.Rr, cal.Tr);
171
 
172
//    for(int i=0; i<nValidSets-1; i++){
81 jakw 173
//        std::cout << i << std::endl;
33 jakw 174
 
81 jakw 175
//        cv::Mat Rci;
176
//        cv::Rodrigues(Rc[i], Rci);
91 jakw 177
//        std::cout << "Rc[i]" << Rci << std::endl;
81 jakw 178
//        std::cout << "Tc[i]" << Tc[i] << std::endl;
179
 
91 jakw 180
//        cv::Mat Rri;
181
//        cv::Rodrigues(Rr[i], Rri);
182
//        std::cout << "Rr[i]" << Rri << std::endl;
81 jakw 183
//        std::cout << "Tr[i]" << Tr[i] << std::endl;
91 jakw 184
 
185
//        cv::Mat Rcr = cv::Mat(cal.Rr)*cv::Mat(Rc[i])*cv::Mat(cal.Rr.t());
186
//        cv::Rodrigues(Rcr, Rcr);
187
//        cv::Mat Tcr = -cv::Mat(cal.Rr)*cv::Mat(Rc[i])*cv::Mat(cal.Rr.t())*cv::Mat(cal.Tr) + cv::Mat(cal.Rr)*cv::Mat(Tc[i]) + cv::Mat(cal.Tr);
188
//        std::cout << "Rcr[i]" << Rcr << std::endl;
189
//        std::cout << "Tcr[i]" << Tcr << std::endl;
81 jakw 190
//        std::cout << std::endl;
91 jakw 191
//    }
81 jakw 192
 
193
 
91 jakw 194
    // Direct rotation axis calibration //
195
    // full camera matrices
196
    cv::Matx34f P0 = cv::Matx34f::eye();
197
    cv::Mat RT1(3, 4, CV_32F);
198
    cv::Mat(cal.R1).copyTo(RT1(cv::Range(0, 3), cv::Range(0, 3)));
199
    cv::Mat(cal.T1).copyTo(RT1(cv::Range(0, 3), cv::Range(3, 4)));
200
    cv::Matx34f P1 = cv::Matx34f(RT1);
81 jakw 201
 
91 jakw 202
    // calibration points in camera 0 frame
203
    std::vector< std::vector<cv::Point3f> > Qcam;
33 jakw 204
 
91 jakw 205
    for(int i=0; i<nValidSets; i++){
206
        std::vector<cv::Point2f> qc0i, qc1i;
81 jakw 207
 
91 jakw 208
        cv::undistortPoints(qc0[i], qc0i, cal.K0, cal.k0);
209
        cv::undistortPoints(qc1[i], qc1i, cal.K1, cal.k1);
88 jakw 210
//        qc0i = qc0[i];
211
//        qc1i = qc1[i];
84 jakw 212
 
91 jakw 213
        cv::Mat Qhom, Qcami;
214
        cv::triangulatePoints(P0, P1, qc0i, qc1i, Qhom);
215
        cvtools::convertMatFromHomogeneous(Qhom, Qcami);
216
        std::vector<cv::Point3f> QcamiPoints;
217
        cvtools::matToPoints3f(Qcami, QcamiPoints);
84 jakw 218
 
91 jakw 219
        Qcam.push_back(QcamiPoints);
220
    }
84 jakw 221
 
91 jakw 222
    cv::Vec3f axis, point;
223
    cvtools::rotationAxisCalibration(Qcam, Qi, axis, point);
84 jakw 224
 
91 jakw 225
    // construct transformation matrix
226
    cv::Vec3f ex = axis.cross(cv::Vec3f(0,0,1.0));
227
    ex = cv::normalize(ex);
228
    cv::Vec3f ez = ex.cross(axis);
229
    ez = cv::normalize(ez);
84 jakw 230
 
91 jakw 231
    cv::Mat RrMat(3, 3, CV_32F);
232
    cv::Mat(ex).copyTo(RrMat.col(0));
233
    cv::Mat(axis).copyTo(RrMat.col(1));
234
    cv::Mat(ez).copyTo(RrMat.col(2));
84 jakw 235
 
91 jakw 236
    cal.Rr = cv::Matx33f(RrMat).t();
237
    cal.Tr = -cv::Matx33f(RrMat).t()*point;
84 jakw 238
 
27 jakw 239
    // Print to std::cout
240
    cal.print();
241
 
242
    // save to (reentrant qsettings object)
33 jakw 243
    settings.setValue("calibration/parameters", QVariant::fromValue(cal));
27 jakw 244
 
245
    emit done();
246
 
22 jakw 247
}