Subversion Repositories seema-scanner

Rev

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