Subversion Repositories seema-scanner

Rev

Rev 195 | Rev 197 | 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
 
196 jakw 8
#include <ceres/ceres.h>
9
 
10
 
11
struct CircleResidual {
12
  CircleResidual(std::vector<cv::Point3f> _pointsOnArc)
13
      : pointsOnArc(_pointsOnArc) {}
14
 
15
  template <typename T>
16
  bool operator()(const T* const point_x, const T* const point_y, const T* const point_z,
17
                  const T* const axis_x, const T* const axis_y, const T* const axis_z,
18
                  T* residual) const {
19
 
20
    cv::Vec3f axis(*axis_x, *axis_y, *axis_z);
21
    cv::Vec3f point(*point_x, *point_y, *point_z);
22
 
23
    unsigned int l = pointsOnArc.size();
24
    std::vector<float> dI(l);
25
    for(unsigned int i=0; i<l; i++){
26
      cv::Vec3f p = cv::Vec3f(pointsOnArc[i]);
27
      // point to line distance
28
      dI[i] = cv::norm((point-p)-(point-p).dot(axis)*axis);
29
    }
30
    float sum = std::accumulate(dI.begin(), dI.end(), 0.0);
31
    float mean = sum / dI.size();
32
    float meanDev = 0;
33
    for(unsigned int k=0; k<l; k++){
34
      meanDev += std::abs(dI[k] - mean);
35
    }
36
    meanDev /= l;
37
 
38
    residual[0] = T(meanDev);
39
 
40
    return true;
41
  }
42
 
43
 private:
44
 
45
  // Observations for one checkerboard corner.
46
  const std::vector<cv::Point3f> pointsOnArc;
47
};
48
 
49
 
50
// Closed form solution to solve for the rotation axis from sets of 3D point coordinates of flat pattern feature points
51
// Algorithm according to Chen et al., Rotation axis calibration of a turntable using constrained global optimization, Optik 2014
52
// DTU, 2014, Jakob Wilm
53
static void rotationAxisCalibration(const std::vector< std::vector<cv::Point3f> > Qcam, const std::vector<cv::Point3f> Qobj, cv::Vec3f &axis, cv::Vec3f &point, float &error){
54
 
55
    // number of frames (points on each arch)
56
    int l = Qcam.size();
57
 
58
    // number of points in each frame
59
    size_t mn = Qobj.size();
60
 
61
    assert(mn == Qcam[0].size());
62
 
63
    // construct matrix for axis determination
64
    cv::Mat M(6, 6, CV_32F, cv::Scalar(0));
65
 
66
    for(int k=0; k<l; k++){
67
        for(unsigned int idx=0; idx<mn; idx++){
68
 
69
//            float i = Qobj[idx].x+4;
70
//            float j = Qobj[idx].y+4;
71
            float i = Qobj[idx].x;
72
            float j = Qobj[idx].y;
73
 
74
            float x = Qcam[k][idx].x;
75
            float y = Qcam[k][idx].y;
76
            float z = Qcam[k][idx].z;
77
 
78
            M += (cv::Mat_<float>(6,6) << x*x, x*y, x*z, x, i*x, j*x,
79
                                            0, y*y, y*z, y, i*y, j*y,
80
                                            0,   0, z*z, z, i*z, j*z,
81
                                            0,   0,   0, 1,   i,   j,
82
                                            0,   0,   0, 0, i*i, i*j,
83
                                            0,   0,   0, 0,   0, j*j);
84
 
85
        }
86
    }
87
 
88
    cv::completeSymm(M, false);
89
 
90
    // solve for axis
91
    std::vector<float> lambda;
92
    cv::Mat u;
93
    cv::eigen(M, lambda, u);
94
 
95
    float minLambda = std::abs(lambda[0]);
96
    int idx = 0;
97
    for(unsigned int i=1; i<lambda.size(); i++){
98
        if(abs(lambda[i]) < minLambda){
99
            minLambda = lambda[i];
100
            idx = i;
101
        }
102
    }
103
 
104
    axis = u.row(idx).colRange(0, 3);
105
    axis = cv::normalize(axis);
106
 
107
    float nx = u.at<float>(idx, 0);
108
    float ny = u.at<float>(idx, 1);
109
    float nz = u.at<float>(idx, 2);
110
    //float d  = u.at<float>(idx, 3);
111
    float dh = u.at<float>(idx, 4);
112
    float dv = u.at<float>(idx, 5);
113
 
114
//    // Paper version: c is initially eliminated
115
//    cv::Mat A(l*mn, mn+2, CV_32F, cv::Scalar(0.0));
116
//    cv::Mat bb(l*mn, 1, CV_32F);
117
 
118
//    for(int k=0; k<l; k++){
119
//        for(unsigned int idx=0; idx<mn; idx++){
120
 
121
//            float i = Qobj[idx].x;
122
//            float j = Qobj[idx].y;
123
 
124
//            float x = Qcam[k][idx].x;
125
//            float y = Qcam[k][idx].y;
126
//            float z = Qcam[k][idx].z;
127
 
128
//            float f = x*x + y*y + z*z + (2*x*nx + 2*y*ny + 2*z*nz)*(i*dh + j*dv);
129
 
130
//            int row = k*mn+idx;
131
//            A.at<float>(row, 0) = 2*x - (2*z*nx)/nz;
132
//            A.at<float>(row, 1) = 2*y - (2*z*ny)/nz;
133
//            A.at<float>(row, idx+2) = 1.0;
134
 
135
//            bb.at<float>(row, 0) = f + (2*z*d)/nz;
136
//        }
137
//    }
138
 
139
//    // solve for point
140
//    cv::Mat abe;
141
//    cv::solve(A, bb, abe, cv::DECOMP_SVD);
142
 
143
//    float a = abe.at<float>(0, 0);
144
//    float b = abe.at<float>(1, 0);
145
//    float c = -(nx*a+ny*b+d)/nz;
146
 
147
    // Our version: solve simultanously for a,b,c
148
    cv::Mat A(l*mn, mn+3, CV_32F, cv::Scalar(0.0));
149
    cv::Mat bb(l*mn, 1, CV_32F);
150
 
151
    for(int k=0; k<l; k++){
152
        for(unsigned int idx=0; idx<mn; idx++){
153
 
154
            float i = Qobj[idx].x;
155
            float j = Qobj[idx].y;
156
 
157
            float x = Qcam[k][idx].x;
158
            float y = Qcam[k][idx].y;
159
            float z = Qcam[k][idx].z;
160
 
161
            float f = x*x + y*y + z*z + (2*x*nx + 2*y*ny + 2*z*nz)*(i*dh + j*dv);
162
 
163
            int row = k*mn+idx;
164
            A.at<float>(row, 0) = 2*x;
165
            A.at<float>(row, 1) = 2*y;
166
            A.at<float>(row, 2) = 2*z;
167
            A.at<float>(row, idx+3) = 1.0;
168
 
169
            bb.at<float>(row, 0) = f;
170
        }
171
    }
172
 
173
    // solve for point
174
    cv::Mat abe;
175
    cv::solve(A, bb, abe, cv::DECOMP_SVD);
176
 
177
    float a = abe.at<float>(0, 0);
178
    float b = abe.at<float>(1, 0);
179
    float c = abe.at<float>(2, 0);
180
 
181
    point[0] = a;
182
    point[1] = b;
183
    point[2] = c;
184
 
185
    // Non-linear optimization using Ceres
186
    double point_x = point[0];
187
    double point_y = point[1];
188
    double point_z = point[2];
189
    double axis_x = axis[0];
190
    double axis_y = axis[1];
191
    double axis_z = axis[2];
192
 
193
    ceres::Problem problem;
194
    // loop through saddle points
195
    for(unsigned int idx=0; idx<mn; idx++){
196
        std::vector<cv::Point3f> pointsOnArch(l);
197
        for(int k=0; k<l; k++){
198
            pointsOnArch[k] = Qcam[k][idx];
199
        }
200
        ceres::CostFunction* cost_function =
201
           new ceres::NumericDiffCostFunction<CircleResidual, ceres::CENTRAL, 1, 1, 1, 1, 1, 1, 1>(
202
               new CircleResidual(pointsOnArch));
203
        problem.AddResidualBlock(cost_function, NULL, &point_x, &point_y, &point_z, &axis_x, &axis_y, &axis_z);
204
    }
205
 
206
    // Run the solver!
207
    ceres::Solver::Options options;
208
    options.linear_solver_type = ceres::DENSE_QR;
209
    options.minimizer_progress_to_stdout = true;
210
    ceres::Solver::Summary summary;
211
    ceres::Solve(options, &problem, &summary);
212
 
213
    std::cout << summary.BriefReport() << "\n";
214
 
215
 
216
    point = cv::Point3f(point_x, point_y, point_z);
217
    axis = cv::Point3f(axis_x, axis_y, axis_z);
218
 
219
 
220
    // Error estimate (mean 3D point deviations from circles around rotation axis)
221
    error = 0;
222
    // loop through saddle points
223
    for(unsigned int idx=0; idx<mn; idx++){
224
 
225
        // vector of distances from rotation axis
226
        std::vector<float> dI(l);
227
        // loop through angular positions
228
        for(int k=0; k<l; k++){
229
            cv::Vec3f p = cv::Vec3f(Qcam[k][idx]);
230
            // point to line distance
231
            dI[k] = cv::norm((point-p)-(point-p).dot(axis)*axis);
232
        }
233
        float sum = std::accumulate(dI.begin(), dI.end(), 0.0);
234
        float mean = sum / dI.size();
235
        float meanDev = 0;
236
        for(int k=0; k<l; k++){
237
            meanDev += std::abs(dI[k] - mean);
238
        }
239
        meanDev /= l;
240
        //std::cout << meanDev << std::endl;
241
        error += meanDev;
242
    }
243
    error /= mn;
244
 
245
}
246
 
27 jakw 247
void SMCalibrationWorker::performCalibration(std::vector<SMCalibrationSet> calibrationData){
22 jakw 248
 
33 jakw 249
    QSettings settings;
250
 
22 jakw 251
    // Number of saddle points on calibration pattern
169 jakw 252
    int checkerCountX = settings.value("calibration/patternSizeX", 22).toInt();
253
    int checkerCountY = settings.value("calibration/patternSizeY", 13).toInt();
33 jakw 254
    cv::Size checkerCount(checkerCountX, checkerCountY);
22 jakw 255
 
167 jakw 256
    unsigned int nSets = calibrationData.size();
22 jakw 257
 
148 jakw 258
    // 2D Points collected for OpenCV's calibration procedures
31 jakw 259
    std::vector< std::vector<cv::Point2f> > qc0, qc1;
137 jakw 260
    std::vector< std::vector<cv::Point2f> > qc0Stereo, qc1Stereo;
261
 
148 jakw 262
    std::vector<bool> success0(nSets), success1(nSets);
263
 
31 jakw 264
    std::vector<float> angles;
22 jakw 265
 
266
    // Loop through calibration sets
167 jakw 267
    for(unsigned int i=0; i<nSets; i++){
22 jakw 268
 
27 jakw 269
        SMCalibrationSet SMCalibrationSetI = calibrationData[i];
25 jakw 270
 
27 jakw 271
        if(!SMCalibrationSetI.checked)
22 jakw 272
            continue;
25 jakw 273
 
274
        // Camera 0
275
        std::vector<cv::Point2f> qci0;
136 jakw 276
 
277
        // Convert to grayscale
123 jakw 278
        cv::Mat gray;
136 jakw 279
        if(SMCalibrationSetI.frame0.channels() == 1)
280
            cv::cvtColor(SMCalibrationSetI.frame0, gray, CV_BayerBG2GRAY);
281
        else
282
            cv::cvtColor(SMCalibrationSetI.frame0, gray, CV_RGB2GRAY);
283
 
25 jakw 284
        // Extract checker corners
148 jakw 285
        success0[i] = cv::findChessboardCorners(gray, checkerCount, qci0, cv::CALIB_CB_ADAPTIVE_THRESH + cv::CALIB_CB_FAST_CHECK);
286
        if(success0[i]){
134 jakw 287
            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 288
            // Draw colored chessboard
120 jakw 289
            cv::Mat color;
136 jakw 290
            if(SMCalibrationSetI.frame0.channels() == 1)
291
                cv::cvtColor(SMCalibrationSetI.frame0, color, CV_BayerBG2RGB);
292
            else
293
                color = SMCalibrationSetI.frame0.clone();
294
 
148 jakw 295
            cvtools::drawChessboardCorners(color, checkerCount, qci0, success0[i], 10);
120 jakw 296
            SMCalibrationSetI.frame0Result = color;
22 jakw 297
        }
298
 
148 jakw 299
        emit newFrameResult(i, 0, success0[i], SMCalibrationSetI.frame0Result);
29 jakw 300
 
25 jakw 301
        // Camera 1
302
        std::vector<cv::Point2f> qci1;
136 jakw 303
 
304
        // Convert to grayscale
305
        if(SMCalibrationSetI.frame1.channels() == 1)
306
            cv::cvtColor(SMCalibrationSetI.frame1, gray, CV_BayerBG2GRAY);
307
        else
308
            cv::cvtColor(SMCalibrationSetI.frame1, gray, CV_RGB2GRAY);
309
 
25 jakw 310
        // Extract checker corners
148 jakw 311
        success1[i] = cv::findChessboardCorners(gray, checkerCount, qci1, cv::CALIB_CB_ADAPTIVE_THRESH + cv::CALIB_CB_FAST_CHECK);
312
        if(success1[i]){
134 jakw 313
            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 314
            // Draw colored chessboard
120 jakw 315
            cv::Mat color;
136 jakw 316
            if(SMCalibrationSetI.frame1.channels() == 1)
317
                cv::cvtColor(SMCalibrationSetI.frame1, color, CV_BayerBG2RGB);
318
            else
319
                color = SMCalibrationSetI.frame1.clone();
320
 
148 jakw 321
            cvtools::drawChessboardCorners(color, checkerCount, qci1, success1[i], 10);
120 jakw 322
            SMCalibrationSetI.frame1Result = color;
22 jakw 323
        }
324
 
148 jakw 325
        emit newFrameResult(i, 1, success1[i], SMCalibrationSetI.frame1Result);
29 jakw 326
 
148 jakw 327
        if(success0[i])
137 jakw 328
            qc0.push_back(qci0);
25 jakw 329
 
148 jakw 330
        if(success1[i])
31 jakw 331
            qc1.push_back(qci1);
137 jakw 332
 
148 jakw 333
        if(success0[i] && success1[i]){
137 jakw 334
            qc0Stereo.push_back(qci0);
335
            qc1Stereo.push_back(qci1);
31 jakw 336
            angles.push_back(SMCalibrationSetI.rotationAngle);
22 jakw 337
        }
338
 
27 jakw 339
        // Show progress
340
        emit newSetProcessed(i);
22 jakw 341
    }
342
 
167 jakw 343
    size_t nValidSets = angles.size();
27 jakw 344
    if(nValidSets < 2){
22 jakw 345
        std::cerr << "Not enough valid calibration sequences!" << std::endl;
29 jakw 346
        emit done();
22 jakw 347
        return;
348
    }
349
 
350
    // Generate world object coordinates [mm]
166 jakw 351
    float checkerSize = settings.value("calibration/squareSize", 10.0).toFloat(); // width and height of one checker square in mm
22 jakw 352
    std::vector<cv::Point3f> Qi;
33 jakw 353
    for (int h=0; h<checkerCount.height; h++)
354
        for (int w=0; w<checkerCount.width; w++)
355
            Qi.push_back(cv::Point3f(checkerSize * w, checkerSize* h, 0.0));
137 jakw 356
 
357
    std::vector< std::vector<cv::Point3f> > Q0, Q1, QStereo;
167 jakw 358
    for(unsigned int i=0; i<qc0.size(); i++)
137 jakw 359
        Q0.push_back(Qi);
167 jakw 360
    for(unsigned int i=0; i<qc1.size(); i++)
137 jakw 361
        Q1.push_back(Qi);
167 jakw 362
    for(unsigned int i=0; i<nValidSets; i++)
137 jakw 363
        QStereo.push_back(Qi);
22 jakw 364
 
365
    // calibrate the cameras
31 jakw 366
    SMCalibrationParameters cal;
367
    cal.frameWidth = calibrationData[0].frame0.cols;
368
    cal.frameHeight = calibrationData[0].frame0.rows;
369
    cv::Size frameSize(cal.frameWidth, cal.frameHeight);
22 jakw 370
 
68 jakw 371
    // determine only k1, k2 for lens distortion
140 jakw 372
    int flags = cv::CALIB_FIX_ASPECT_RATIO + cv::CALIB_FIX_K3 + cv::CALIB_ZERO_TANGENT_DIST + cv::CALIB_FIX_PRINCIPAL_POINT;
33 jakw 373
    // Note: several of the output arguments below must be cv::Mat, otherwise segfault
374
    std::vector<cv::Mat> cam_rvecs0, cam_tvecs0;
137 jakw 375
    cal.cam0_error = cv::calibrateCamera(Q0, qc0, frameSize, cal.K0, cal.k0, cam_rvecs0, cam_tvecs0, flags,
134 jakw 376
                                         cv::TermCriteria(cv::TermCriteria::COUNT+cv::TermCriteria::EPS, 100, DBL_EPSILON));
377
//std::cout << cal.k0 << std::endl;
120 jakw 378
//    // refine extrinsics for camera 0
379
//    for(int i=0; i<Q.size(); i++)
380
//        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 381
 
33 jakw 382
    std::vector<cv::Mat> cam_rvecs1, cam_tvecs1;
137 jakw 383
    cal.cam1_error = cv::calibrateCamera(Q1, qc1, frameSize, cal.K1, cal.k1, cam_rvecs1, cam_tvecs1, flags,
134 jakw 384
                                         cv::TermCriteria(cv::TermCriteria::COUNT+cv::TermCriteria::EPS, 100, DBL_EPSILON));
385
//std::cout << cal.k1 << std::endl;
111 jakw 386
    // stereo calibration
136 jakw 387
    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 388
    cv::Mat E, F, R1, T1;
137 jakw 389
    cal.stereo_error = cv::stereoCalibrate(QStereo, qc0Stereo, qc1Stereo, cal.K0, cal.k0, cal.K1, cal.k1,
33 jakw 390
                                              frameSize, R1, T1, E, F,
134 jakw 391
                                              cv::TermCriteria(cv::TermCriteria::COUNT + cv::TermCriteria::EPS, 200, DBL_EPSILON),
22 jakw 392
                                              flags_stereo);
393
 
33 jakw 394
    cal.R1 = R1;
395
    cal.T1 = T1;
396
    cal.E = E;
397
    cal.F = F;
398
 
148 jakw 399
    // Determine per-view reprojection errors:
400
    cal.cam0_errors_per_view.resize(nSets);
401
    int idx = 0;
402
    for(unsigned int i = 0; i < nSets; ++i){
403
        if(success0[i]){
404
            int n = (int)Q0[idx].size();
405
            std::vector<cv::Point2f> qc_proj;
406
            cv::projectPoints(cv::Mat(Q0[idx]), cam_rvecs0[idx], cam_tvecs0[idx], cal.K0,  cal.k0, qc_proj);
407
            float err = 0;
167 jakw 408
            for(unsigned int j=0; j<qc_proj.size(); j++){
148 jakw 409
                cv::Point2f d = qc0[idx][j] - qc_proj[j];
410
                err += cv::sqrt(d.x*d.x + d.y*d.y);
411
            }
412
            cal.cam0_errors_per_view[i] = (float)err/n;
413
            idx++;
414
        } else
415
            cal.cam0_errors_per_view[i] = NAN;
416
    }
417
    cal.cam1_errors_per_view.resize(nSets);
418
    idx = 0;
419
    for(unsigned int i = 0; i < nSets; ++i){
420
        if(success1[i]){
421
            int n = (int)Q1[idx].size();
422
            std::vector<cv::Point2f> qc_proj;
423
            cv::projectPoints(cv::Mat(Q1[idx]), cam_rvecs1[idx], cam_tvecs1[idx], cal.K1,  cal.k1, qc_proj);
424
            float err = 0;
167 jakw 425
            for(unsigned int j=0; j<qc_proj.size(); j++){
148 jakw 426
                cv::Point2f d = qc1[idx][j] - qc_proj[j];
427
                err += cv::sqrt(d.x*d.x + d.y*d.y);
428
            }
429
            cal.cam1_errors_per_view[i] = (float)err/n;
430
            idx++;
431
       } else
432
            cal.cam1_errors_per_view[i] = NAN;
433
    }
434
 
91 jakw 435
//    // hand-eye calibration
436
//    std::vector<cv::Matx33f> Rc(nValidSets - 1); // rotations/translations of the checkerboard in camera 0 reference frame
437
//    std::vector<cv::Vec3f> Tc(nValidSets - 1);
438
//    std::vector<cv::Matx33f> Rr(nValidSets - 1); // in rotation stage reference frame
439
//    std::vector<cv::Vec3f> Tr(nValidSets - 1);
440
//    for(int i=0; i<nValidSets-1; i++){
441
//        // relative transformations in camera
442
//        cv::Mat cRw1, cRw2;
443
//        cv::Rodrigues(cam_rvecs0[i], cRw1);
444
//        cv::Rodrigues(cam_rvecs0[i+1], cRw2);
445
//        cv::Mat cTw1 = cam_tvecs0[i];
446
//        cv::Mat cTw2 = cam_tvecs0[i+1];
447
//        cv::Mat w1Rc = cRw1.t();
448
//        cv::Mat w1Tc = -cRw1.t()*cTw1;
449
//        Rc[i] = cv::Mat(cRw2*w1Rc);
450
//        Tc[i] = cv::Mat(cRw2*w1Tc+cTw2);
31 jakw 451
 
91 jakw 452
//        // relative transformations in rotation stage
453
//        // we define the rotation axis to be in origo, pointing in positive y direction
454
//        float angleRadians = (angles[i+1]-angles[i])/180.0*M_PI;
455
//        cv::Vec3f rot_rvec(0.0, -angleRadians, 0.0);
456
//        cv::Mat Rri;
457
//        cv::Rodrigues(rot_rvec, Rri);
458
//        Rr[i] = Rri;
459
//        Tr[i] = 0.0;
33 jakw 460
 
91 jakw 461
////        std::cout << i << std::endl;
462
////        std::cout << "cTw1" << cTw1 << std::endl;
463
////        std::cout << "cTw2" << cTw2 << std::endl;
464
////        std::cout << "w2Rc" << w2Rc << std::endl;
465
////        std::cout << "w2Tc" << w2Tc << std::endl;
466
 
467
////        std::cout << "w2Rc" << w2Rc << std::endl;
468
////        std::cout << "w2Tc" << w2Tc << std::endl;
469
 
470
////        cv::Mat Rci;
471
////        cv::Rodrigues(Rc[i], Rci);
472
////        std::cout << "Rci" << Rci << std::endl;
473
////        std::cout << "Tc[i]" << Tc[i] << std::endl;
474
 
475
////        std::cout << "rot_rvec" << rot_rvec << std::endl;
476
////        std::cout << "Tr[i]" << Tr[i] << std::endl;
477
////        std::cout << std::endl;
478
//    }
479
 
480
//    // determine the transformation from rotation stage to camera 0
481
//    cvtools::handEyeCalibrationTsai(Rc, Tc, Rr, Tr, cal.Rr, cal.Tr);
482
 
483
//    for(int i=0; i<nValidSets-1; i++){
81 jakw 484
//        std::cout << i << std::endl;
33 jakw 485
 
81 jakw 486
//        cv::Mat Rci;
487
//        cv::Rodrigues(Rc[i], Rci);
91 jakw 488
//        std::cout << "Rc[i]" << Rci << std::endl;
81 jakw 489
//        std::cout << "Tc[i]" << Tc[i] << std::endl;
490
 
91 jakw 491
//        cv::Mat Rri;
492
//        cv::Rodrigues(Rr[i], Rri);
493
//        std::cout << "Rr[i]" << Rri << std::endl;
81 jakw 494
//        std::cout << "Tr[i]" << Tr[i] << std::endl;
91 jakw 495
 
496
//        cv::Mat Rcr = cv::Mat(cal.Rr)*cv::Mat(Rc[i])*cv::Mat(cal.Rr.t());
497
//        cv::Rodrigues(Rcr, Rcr);
498
//        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);
499
//        std::cout << "Rcr[i]" << Rcr << std::endl;
500
//        std::cout << "Tcr[i]" << Tcr << std::endl;
81 jakw 501
//        std::cout << std::endl;
91 jakw 502
//    }
81 jakw 503
 
504
 
91 jakw 505
    // Direct rotation axis calibration //
506
    // full camera matrices
507
    cv::Matx34f P0 = cv::Matx34f::eye();
508
    cv::Mat RT1(3, 4, CV_32F);
509
    cv::Mat(cal.R1).copyTo(RT1(cv::Range(0, 3), cv::Range(0, 3)));
510
    cv::Mat(cal.T1).copyTo(RT1(cv::Range(0, 3), cv::Range(3, 4)));
511
    cv::Matx34f P1 = cv::Matx34f(RT1);
81 jakw 512
 
91 jakw 513
    // calibration points in camera 0 frame
514
    std::vector< std::vector<cv::Point3f> > Qcam;
33 jakw 515
 
167 jakw 516
    for(unsigned int i=0; i<nValidSets; i++){
91 jakw 517
        std::vector<cv::Point2f> qc0i, qc1i;
81 jakw 518
 
195 jakw 519
        cv::undistortPoints(qc0Stereo[i], qc0i, cal.K0, cal.k0);
520
        cv::undistortPoints(qc1Stereo[i], qc1i, cal.K1, cal.k1);
88 jakw 521
//        qc0i = qc0[i];
522
//        qc1i = qc1[i];
84 jakw 523
 
91 jakw 524
        cv::Mat Qhom, Qcami;
525
        cv::triangulatePoints(P0, P1, qc0i, qc1i, Qhom);
526
        cvtools::convertMatFromHomogeneous(Qhom, Qcami);
527
        std::vector<cv::Point3f> QcamiPoints;
528
        cvtools::matToPoints3f(Qcami, QcamiPoints);
84 jakw 529
 
91 jakw 530
        Qcam.push_back(QcamiPoints);
531
    }
84 jakw 532
 
176 jakw 533
//    cv::Mat QcamMat(Qcam.size(), Qcam[0].size(), CV_32FC3);
534
//    for(int i=0; i<Qcam.size(); i++)
535
//        for(int j=0; j<Qcam[0].size(); j++)
536
//            QcamMat.at<cv::Point3f>(i,j) = Qcam[i][j];
537
//    cvtools::writeMat(QcamMat, "Qcam.mat", "Qcam");
538
 
91 jakw 539
    cv::Vec3f axis, point;
176 jakw 540
    float rot_axis_error;
196 jakw 541
    rotationAxisCalibration(Qcam, Qi, axis, point, rot_axis_error);
84 jakw 542
 
91 jakw 543
    // construct transformation matrix
544
    cv::Vec3f ex = axis.cross(cv::Vec3f(0,0,1.0));
545
    ex = cv::normalize(ex);
546
    cv::Vec3f ez = ex.cross(axis);
547
    ez = cv::normalize(ez);
84 jakw 548
 
91 jakw 549
    cv::Mat RrMat(3, 3, CV_32F);
550
    cv::Mat(ex).copyTo(RrMat.col(0));
551
    cv::Mat(axis).copyTo(RrMat.col(1));
552
    cv::Mat(ez).copyTo(RrMat.col(2));
84 jakw 553
 
91 jakw 554
    cal.Rr = cv::Matx33f(RrMat).t();
555
    cal.Tr = -cv::Matx33f(RrMat).t()*point;
176 jakw 556
    cal.rot_axis_error = rot_axis_error;
84 jakw 557
 
27 jakw 558
    // Print to std::cout
559
    cal.print();
560
 
561
    // save to (reentrant qsettings object)
33 jakw 562
    settings.setValue("calibration/parameters", QVariant::fromValue(cal));
27 jakw 563
 
564
    emit done();
565
 
22 jakw 566
}