Subversion Repositories seema-scanner

Rev

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