Subversion Repositories seema-scanner

Rev

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