Subversion Repositories seema-scanner

Rev

Rev 228 | Rev 242 | 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>
225 jakw 7
#include <QTextStream>
22 jakw 8
 
196 jakw 9
#include <ceres/ceres.h>
10
 
11
// Closed form solution to solve for the rotation axis from sets of 3D point coordinates of flat pattern feature points
12
// Algorithm according to Chen et al., Rotation axis calibration of a turntable using constrained global optimization, Optik 2014
13
// DTU, 2014, Jakob Wilm
225 jakw 14
static void rotationAxisEstimation(const std::vector< std::vector<cv::Point3f> > Qcam,
15
                                   const std::vector<cv::Point3f> Qobj,
16
                                   cv::Vec3f &axis, cv::Vec3f &point){
207 flgw 17
    assert(Qobj.size() == Qcam[0].size());
196 jakw 18
 
19
    // number of frames (points on each arch)
20
    int l = Qcam.size();
21
 
22
    // number of points in each frame
23
    size_t mn = Qobj.size();
24
 
25
    // construct matrix for axis determination
26
    cv::Mat M(6, 6, CV_32F, cv::Scalar(0));
27
 
28
    for(int k=0; k<l; k++){
29
        for(unsigned int idx=0; idx<mn; idx++){
30
 
207 flgw 31
            //            float i = Qobj[idx].x+4;
32
            //            float j = Qobj[idx].y+4;
196 jakw 33
            float i = Qobj[idx].x;
34
            float j = Qobj[idx].y;
35
 
36
            float x = Qcam[k][idx].x;
37
            float y = Qcam[k][idx].y;
38
            float z = Qcam[k][idx].z;
39
 
40
            M += (cv::Mat_<float>(6,6) << x*x, x*y, x*z, x, i*x, j*x,
207 flgw 41
                  0, y*y, y*z, y, i*y, j*y,
42
                  0,   0, z*z, z, i*z, j*z,
43
                  0,   0,   0, 1,   i,   j,
44
                  0,   0,   0, 0, i*i, i*j,
45
                  0,   0,   0, 0,   0, j*j);
196 jakw 46
 
47
        }
48
    }
49
 
50
    cv::completeSymm(M, false);
51
 
52
    // solve for axis
53
    std::vector<float> lambda;
54
    cv::Mat u;
55
    cv::eigen(M, lambda, u);
56
 
57
    float minLambda = std::abs(lambda[0]);
58
    int idx = 0;
59
    for(unsigned int i=1; i<lambda.size(); i++){
60
        if(abs(lambda[i]) < minLambda){
61
            minLambda = lambda[i];
62
            idx = i;
63
        }
64
    }
65
 
66
    axis = u.row(idx).colRange(0, 3);
67
    axis = cv::normalize(axis);
68
 
69
    float nx = u.at<float>(idx, 0);
70
    float ny = u.at<float>(idx, 1);
71
    float nz = u.at<float>(idx, 2);
72
    //float d  = u.at<float>(idx, 3);
73
    float dh = u.at<float>(idx, 4);
74
    float dv = u.at<float>(idx, 5);
75
 
207 flgw 76
    // Paper version: c is initially eliminated
77
    /*cv::Mat A(l*mn, mn+2, CV_32F, cv::Scalar(0.0));
78
        cv::Mat bb(l*mn, 1, CV_32F);
196 jakw 79
 
207 flgw 80
        for(int k=0; k<l; k++){
81
            for(unsigned int idx=0; idx<mn; idx++){
196 jakw 82
 
207 flgw 83
                float i = Qobj[idx].x;
84
                float j = Qobj[idx].y;
196 jakw 85
 
207 flgw 86
                float x = Qcam[k][idx].x;
87
                float y = Qcam[k][idx].y;
88
                float z = Qcam[k][idx].z;
196 jakw 89
 
207 flgw 90
                float f = x*x + y*y + z*z + (2*x*nx + 2*y*ny + 2*z*nz)*(i*dh + j*dv);
196 jakw 91
 
207 flgw 92
                int row = k*mn+idx;
93
                A.at<float>(row, 0) = 2*x - (2*z*nx)/nz;
94
                A.at<float>(row, 1) = 2*y - (2*z*ny)/nz;
95
                A.at<float>(row, idx+2) = 1.0;
196 jakw 96
 
207 flgw 97
                bb.at<float>(row, 0) = f + (2*z*d)/nz;
98
            }
99
        }
196 jakw 100
 
207 flgw 101
        // solve for point
102
        cv::Mat abe;
103
        cv::solve(A, bb, abe, cv::DECOMP_SVD);
196 jakw 104
 
207 flgw 105
        float a = abe.at<float>(0, 0);
106
        float b = abe.at<float>(1, 0);
107
        float c = -(nx*a+ny*b+d)/nz;
108
        */
196 jakw 109
 
110
    // Our version: solve simultanously for a,b,c
111
    cv::Mat A(l*mn, mn+3, CV_32F, cv::Scalar(0.0));
112
    cv::Mat bb(l*mn, 1, CV_32F);
113
 
114
    for(int k=0; k<l; k++){
115
        for(unsigned int idx=0; idx<mn; idx++){
116
 
117
            float i = Qobj[idx].x;
118
            float j = Qobj[idx].y;
119
 
120
            float x = Qcam[k][idx].x;
121
            float y = Qcam[k][idx].y;
122
            float z = Qcam[k][idx].z;
123
 
124
            float f = x*x + y*y + z*z + (2*x*nx + 2*y*ny + 2*z*nz)*(i*dh + j*dv);
125
 
126
            int row = k*mn+idx;
127
            A.at<float>(row, 0) = 2*x;
128
            A.at<float>(row, 1) = 2*y;
129
            A.at<float>(row, 2) = 2*z;
130
            A.at<float>(row, idx+3) = 1.0;
131
 
132
            bb.at<float>(row, 0) = f;
133
        }
134
    }
135
 
136
    // solve for point
137
    cv::Mat abe;
138
    cv::solve(A, bb, abe, cv::DECOMP_SVD);
139
 
140
    float a = abe.at<float>(0, 0);
141
    float b = abe.at<float>(1, 0);
142
    float c = abe.at<float>(2, 0);
143
 
144
    point[0] = a;
145
    point[1] = b;
146
    point[2] = c;
147
 
225 jakw 148
}
149
 
150
struct CircleResidual {
151
    CircleResidual(std::vector<cv::Point3f> _pointsOnArc)
152
        : pointsOnArc(_pointsOnArc) {}
153
 
154
    template <typename T>
155
    bool operator()(const T* point, const T* axis, T* residual) const {
156
 
157
        T axisSqNorm = axis[0]*axis[0] + axis[1]*axis[1] + axis[2]*axis[2];
158
 
159
        unsigned int l = pointsOnArc.size();
160
        std::vector<T> dI(l);
161
 
162
        // note, this is automatically initialized to 0
163
        T sum(0.0);
164
 
165
        for(unsigned int i=0; i<l; i++){
166
            cv::Point3d p = pointsOnArc[i];
167
            //T p[3] = {pointsOnArc[i].x, pointsOnArc[i].y, pointsOnArc[i].z};
168
 
169
            // point to line distance
170
            T dotProd = (point[0]-p.x)*axis[0] + (point[1]-p.y)*axis[1] + (point[2]-p.z)*axis[2];
171
            T dIx = point[0] - p.x - (dotProd*axis[0]/axisSqNorm);
172
            T dIy = point[1] - p.y - (dotProd*axis[1]/axisSqNorm);
173
            T dIz = point[2] - p.z - (dotProd*axis[2]/axisSqNorm);
174
            dI[i] = ceres::sqrt(dIx*dIx + dIy*dIy + dIz*dIz);
175
 
176
            sum += dI[i];
177
        }
178
 
179
        T mean = sum / double(l);
180
 
181
        for(unsigned int i=0; i<l; i++){
182
            residual[i] = dI[i] - mean;
183
        }
184
 
185
        return true;
186
    }
187
 
188
    private:
189
        // Observations for one checkerboard corner.
190
        const std::vector<cv::Point3f> pointsOnArc;
191
};
192
 
193
static void rotationAxisOptimization(const std::vector< std::vector<cv::Point3f> > Qcam, const std::vector<cv::Point3f> Qobj, cv::Vec3f &axis, cv::Vec3f &point, float &error){
194
 
195
    // number of frames (points on each arch)
196
    size_t l = Qcam.size();
197
 
198
    // number of points in each frame
199
    size_t mn = Qobj.size();
200
 
201
    // read initial guess
197 jakw 202
    double pointArray[] = {point[0], point[1], point[2]};
203
    double axisArray[] = {axis[0], axis[1], axis[2]};
196 jakw 204
 
205
    ceres::Problem problem;
225 jakw 206
 
196 jakw 207
    // loop through saddle points
208
    for(unsigned int idx=0; idx<mn; idx++){
209
        std::vector<cv::Point3f> pointsOnArch(l);
225 jakw 210
        for(unsigned int k=0; k<l; k++){
196 jakw 211
            pointsOnArch[k] = Qcam[k][idx];
212
        }
213
        ceres::CostFunction* cost_function =
207 flgw 214
                new ceres::AutoDiffCostFunction<CircleResidual, ceres::DYNAMIC, 3, 3>(
215
                    new CircleResidual(pointsOnArch), l);
197 jakw 216
        problem.AddResidualBlock(cost_function, NULL, pointArray, axisArray);
196 jakw 217
    }
218
 
219
    // Run the solver!
220
    ceres::Solver::Options options;
221
    options.linear_solver_type = ceres::DENSE_QR;
222
    options.minimizer_progress_to_stdout = true;
223
    ceres::Solver::Summary summary;
224
    ceres::Solve(options, &problem, &summary);
225
 
226
    std::cout << summary.BriefReport() << "\n";
227
 
197 jakw 228
    point = cv::Vec3f(pointArray[0], pointArray[1], pointArray[2]);
229
    axis = cv::Vec3f(axisArray[0], axisArray[1], axisArray[2]);
230
    axis /= cv::norm(axis);
196 jakw 231
 
232
 
197 jakw 233
    // Error estimate (sum of squared differences)
196 jakw 234
    error = 0;
235
    // loop through saddle points
236
    for(unsigned int idx=0; idx<mn; idx++){
237
 
238
        // vector of distances from rotation axis
239
        std::vector<float> dI(l);
240
        // loop through angular positions
225 jakw 241
        for(unsigned int k=0; k<l; k++){
196 jakw 242
            cv::Vec3f p = cv::Vec3f(Qcam[k][idx]);
243
            // point to line distance
244
            dI[k] = cv::norm((point-p)-(point-p).dot(axis)*axis);
245
        }
246
        float sum = std::accumulate(dI.begin(), dI.end(), 0.0);
247
        float mean = sum / dI.size();
198 jakw 248
        float meanDev = 0;
225 jakw 249
        for(unsigned int k=0; k<l; k++){
198 jakw 250
            meanDev += std::abs(dI[k] - mean);
196 jakw 251
        }
198 jakw 252
        meanDev /= l;
253
        error += meanDev;
196 jakw 254
    }
198 jakw 255
    error /= mn;
196 jakw 256
}
257
 
225 jakw 258
static std::vector<cv::Point3f> generateWorldCoords(const cv::Size checkerCount, const float checkerSize){
259
 
260
    std::vector<cv::Point3f> Qi;
261
    for (int h=0; h<checkerCount.height; h++)
262
        for (int w=0; w<checkerCount.width; w++)
263
            Qi.push_back(cv::Point3f(checkerSize * w, checkerSize* h, 0.0));
264
 
265
    return Qi;
266
}
267
 
268
static bool detectCheckerBoardCorners(const cv::Size & checkerCount,
269
                                    const cv::Mat & frame,
270
                                    cv::Mat & frameResult,
271
                                    std::vector<cv::Point2f> & qc){
206 flgw 272
    // Convert to grayscale
273
    cv::Mat gray;
225 jakw 274
    if(frame.channels() == 1)
275
        cv::cvtColor(frame, gray, CV_BayerBG2GRAY);
206 flgw 276
    else
225 jakw 277
        cv::cvtColor(frame, gray, CV_RGB2GRAY);
206 flgw 278
 
279
    // Extract checker corners
225 jakw 280
    bool success = cv::findChessboardCorners(gray, checkerCount, qc, cv::CALIB_CB_ADAPTIVE_THRESH + cv::CALIB_CB_FAST_CHECK);
206 flgw 281
    if(success){
225 jakw 282
        cv::cornerSubPix(gray, qc, cv::Size(6, 6), cv::Size(1, 1), cv::TermCriteria(CV_TERMCRIT_EPS + CV_TERMCRIT_ITER, 20, 0.0001));
206 flgw 283
        // Draw colored chessboard
225 jakw 284
        if(frame.channels() == 1)
285
            cv::cvtColor(frame, frameResult, CV_BayerBG2RGB);
206 flgw 286
        else
225 jakw 287
            frameResult = frame.clone();
206 flgw 288
 
225 jakw 289
        cvtools::drawChessboardCorners(frameResult, checkerCount, qc, success, 10);
228 jakw 290
    } else {
291
        qc.clear();
206 flgw 292
    }
293
    return success;
294
}
295
 
225 jakw 296
void SMCalibrationWorker::checkerboardDetection(SMCalibrationSet calibrationSet){
22 jakw 297
 
207 flgw 298
    QSettings settings;
225 jakw 299
    cv::Size checkerCount(cv::Size(settings.value("calibration/patternSizeX", 22).toInt(), settings.value("calibration/patternSizeY", 13).toInt()));
22 jakw 300
 
225 jakw 301
    bool success0 = detectCheckerBoardCorners(checkerCount, calibrationSet.frame0, calibrationSet.frame0Result, calibrationSet.qc0);
228 jakw 302
    if(!success0){
303
//        calibrationSet.qc0.clear();
225 jakw 304
        emit logMessage(QString("Could not detect checkerboard on set %1 camera0").arg(calibrationSet.id));
228 jakw 305
    }
22 jakw 306
 
225 jakw 307
    bool success1 = detectCheckerBoardCorners(checkerCount, calibrationSet.frame1, calibrationSet.frame1Result, calibrationSet.qc1);
228 jakw 308
    if(!success1){
309
//        calibrationSet.qc1.clear();
225 jakw 310
        emit logMessage(QString("Could not detect checkerboard on set %1 camera1").arg(calibrationSet.id));
228 jakw 311
    }
25 jakw 312
 
225 jakw 313
    emit newCheckerboardResult(calibrationSet.id, calibrationSet);
25 jakw 314
 
207 flgw 315
}
25 jakw 316
 
225 jakw 317
void SMCalibrationWorker::cameraCalibration(std::vector<SMCalibrationSet> calibrationData){
137 jakw 318
 
225 jakw 319
    QSettings settings;
320
    cv::Size checkerCount(cv::Size(settings.value("calibration/patternSizeX", 22).toInt(), settings.value("calibration/patternSizeY", 13).toInt()));
22 jakw 321
 
225 jakw 322
    unsigned int nSets = calibrationData.size();
22 jakw 323
 
225 jakw 324
    // 2D Points collected for OpenCV's calibration procedures
325
    std::vector< std::vector<cv::Point2f> > qc0, qc1, qc0Stereo, qc1Stereo;
207 flgw 326
 
236 jakw 327
    for(unsigned int i=0; i<nSets; i++){
207 flgw 328
 
225 jakw 329
        if(!calibrationData[i].selected)
330
            continue;
207 flgw 331
 
225 jakw 332
        // Note: avoiding push_back has only minor theoretical value
333
        if(!calibrationData[i].qc0.empty())
334
            qc0.push_back(calibrationData[i].qc0);
207 flgw 335
 
225 jakw 336
        if(!calibrationData[i].qc1.empty())
337
            qc1.push_back(calibrationData[i].qc1);
207 flgw 338
 
225 jakw 339
        if(!calibrationData[i].qc0.empty() && !calibrationData[i].qc1.empty()){
340
            qc0Stereo.push_back(calibrationData[i].qc0);
341
            qc1Stereo.push_back(calibrationData[i].qc1);
207 flgw 342
        }
22 jakw 343
    }
344
 
345
    // Generate world object coordinates [mm]
225 jakw 346
    std::vector<cv::Point3f> Qi = generateWorldCoords(checkerCount, settings.value("calibration/squareSize", 10.0).toFloat());
137 jakw 347
 
225 jakw 348
    std::vector< std::vector<cv::Point3f> > Q0(qc0.size(), Qi), Q1(qc1.size(), Qi), QStereo(qc0Stereo.size(), Qi);
22 jakw 349
 
225 jakw 350
    // Calibrate the cameras
31 jakw 351
    SMCalibrationParameters cal;
352
    cal.frameWidth = calibrationData[0].frame0.cols;
353
    cal.frameHeight = calibrationData[0].frame0.rows;
354
    cv::Size frameSize(cal.frameWidth, cal.frameHeight);
22 jakw 355
 
68 jakw 356
    // determine only k1, k2 for lens distortion
140 jakw 357
    int flags = cv::CALIB_FIX_ASPECT_RATIO + cv::CALIB_FIX_K3 + cv::CALIB_ZERO_TANGENT_DIST + cv::CALIB_FIX_PRINCIPAL_POINT;
225 jakw 358
 
33 jakw 359
    std::vector<cv::Mat> cam_rvecs0, cam_tvecs0;
225 jakw 360
 
361
    cal.cam0_error = cv::calibrateCamera(Q0, qc0, frameSize, cal.K0, cal.k0, cam_rvecs0, cam_tvecs0, cal.cam0_intrinsic_std, cal.cam0_extrinsic_std, cal.cam0_errors_per_view, flags,
134 jakw 362
                                         cv::TermCriteria(cv::TermCriteria::COUNT+cv::TermCriteria::EPS, 100, DBL_EPSILON));
86 jakw 363
 
33 jakw 364
    std::vector<cv::Mat> cam_rvecs1, cam_tvecs1;
225 jakw 365
    cal.cam1_error = cv::calibrateCamera(Q1, qc1, frameSize, cal.K1, cal.k1, cam_rvecs1, cam_tvecs1, cal.cam1_intrinsic_std, cal.cam1_extrinsic_std, cal.cam1_errors_per_view, flags,
134 jakw 366
                                         cv::TermCriteria(cv::TermCriteria::COUNT+cv::TermCriteria::EPS, 100, DBL_EPSILON));
225 jakw 367
 
368
    // Stereo calibration
136 jakw 369
    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 370
    cv::Mat E, F, R1, T1;
22 jakw 371
 
225 jakw 372
    #if CV_MAJOR_VERSION < 3
207 flgw 373
        cal.stereo_error = cv::stereoCalibrate(QStereo, qc0Stereo, qc1Stereo, cal.K0, cal.k0, cal.K1, cal.k1,
374
                                               frameSize, R1, T1, E, F,
375
                                               cv::TermCriteria(cv::TermCriteria::COUNT + cv::TermCriteria::EPS, 200, DBL_EPSILON),
376
                                               flags_stereo);
225 jakw 377
    #else
207 flgw 378
        cal.stereo_error = cv::stereoCalibrate(QStereo, qc0Stereo, qc1Stereo, cal.K0, cal.k0, cal.K1, cal.k1,
225 jakw 379
                                               frameSize, R1, T1, E, F, flags_stereo,
207 flgw 380
                                               cv::TermCriteria(cv::TermCriteria::COUNT + cv::TermCriteria::EPS, 200, DBL_EPSILON));
225 jakw 381
    #endif
207 flgw 382
 
33 jakw 383
    cal.R1 = R1;
384
    cal.T1 = T1;
385
    cal.E = E;
386
    cal.F = F;
387
 
225 jakw 388
    // Print to log
389
    std::stringstream out;
390
    out << "## Camera Calibration ##" << std::endl
391
        << "No. images used for intrinsics of cam0: " << qc0.size() << std::endl
392
        << "No. images used for intrinsics of cam1: " << qc1.size() << std::endl
393
        << "No. images used for stereo calibration: " << qc0Stereo.size() << std::endl;
394
    cal.printCamera(out);
395
    out << std::endl << std::endl;
396
    emit logMessage(QString::fromStdString(out.str()));
148 jakw 397
 
225 jakw 398
    // save to (reentrant) qsettings object
399
    settings.setValue("calibration/parameters", QVariant::fromValue(cal));
31 jakw 400
 
225 jakw 401
    emit done();
402
}
33 jakw 403
 
91 jakw 404
 
225 jakw 405
void SMCalibrationWorker::rotationStageCalibration(std::vector<SMCalibrationSet> calibrationData){
91 jakw 406
 
225 jakw 407
    int nSets = calibrationData.size();
91 jakw 408
 
225 jakw 409
    std::vector< std::vector<cv::Point2f> > qc0Stereo, qc1Stereo;
410
    for(int i=0; i<nSets; i++){
91 jakw 411
 
225 jakw 412
        if(!calibrationData[i].selected)
413
            continue;
91 jakw 414
 
225 jakw 415
        // Note: avoiding push_back has only minor theoretical value
416
        if(!calibrationData[i].qc0.empty() && !calibrationData[i].qc1.empty()){
417
            qc0Stereo.push_back(calibrationData[i].qc0);
418
            qc1Stereo.push_back(calibrationData[i].qc1);
419
        }
420
    }
33 jakw 421
 
225 jakw 422
    QSettings settings;
423
    SMCalibrationParameters cal = settings.value("calibration/parameters").value<SMCalibrationParameters>();
81 jakw 424
 
225 jakw 425
    if(qc0Stereo.size() > 2){
207 flgw 426
        // Generate world object coordinates [mm]
225 jakw 427
        const cv::Size checkerCount(cv::Size(settings.value("calibration/patternSizeX", 22).toInt(),settings.value("calibration/patternSizeY", 13).toInt()));
428
        const float checkerSize = settings.value("calibration/squareSize", 10.0).toFloat();
429
        std::vector<cv::Point3f> Qi = generateWorldCoords(checkerCount, checkerSize);
91 jakw 430
 
207 flgw 431
        // Direct rotation axis calibration //
432
        // full camera matrices
433
        cv::Matx34f P0 = cv::Matx34f::eye();
434
        cv::Mat RT1(3, 4, CV_32F);
435
        cv::Mat(cal.R1).copyTo(RT1(cv::Range(0, 3), cv::Range(0, 3)));
436
        cv::Mat(cal.T1).copyTo(RT1(cv::Range(0, 3), cv::Range(3, 4)));
437
        cv::Matx34f P1 = cv::Matx34f(RT1);
81 jakw 438
 
207 flgw 439
        // calibration points in camera 0 frame
440
        std::vector< std::vector<cv::Point3f> > Qcam(qc0Stereo.size());
225 jakw 441
 
442
        #pragma omp parallel for
207 flgw 443
        for(unsigned int i=0; i<qc0Stereo.size(); i++){
444
            std::vector<cv::Point2f> qc0i, qc1i;
81 jakw 445
 
207 flgw 446
            cv::undistortPoints(qc0Stereo[i], qc0i, cal.K0, cal.k0);
447
            cv::undistortPoints(qc1Stereo[i], qc1i, cal.K1, cal.k1);
81 jakw 448
 
207 flgw 449
            cv::Mat Qhom, Qcami;
450
            cv::triangulatePoints(P0, P1, qc0i, qc1i, Qhom);
451
            cvtools::convertMatFromHomogeneous(Qhom, Qcami);
452
            std::vector<cv::Point3f> QcamiPoints;
453
            cvtools::matToPoints3f(Qcami, QcamiPoints);
33 jakw 454
 
207 flgw 455
            Qcam[i] = QcamiPoints;
456
        }
81 jakw 457
 
207 flgw 458
        cv::Vec3f axis, point;
459
        float rot_axis_error;
225 jakw 460
        rotationAxisEstimation(Qcam, Qi, axis, point);
461
        rotationAxisOptimization(Qcam, Qi, axis, point, rot_axis_error);
84 jakw 462
 
207 flgw 463
        // construct transformation matrix
464
        cv::Vec3f ex = axis.cross(cv::Vec3f(0,0,1.0));
465
        ex = cv::normalize(ex);
466
        cv::Vec3f ez = ex.cross(axis);
467
        ez = cv::normalize(ez);
84 jakw 468
 
207 flgw 469
        cv::Mat RrMat(3, 3, CV_32F);
470
        cv::Mat(ex).copyTo(RrMat.col(0));
471
        cv::Mat(axis).copyTo(RrMat.col(1));
472
        cv::Mat(ez).copyTo(RrMat.col(2));
473
 
474
        cal.Rr = cv::Matx33f(RrMat).t();
475
        cal.Tr = -cv::Matx33f(RrMat).t()*point;
476
        cal.rot_axis_error = rot_axis_error;
225 jakw 477
    } else {
207 flgw 478
        cal.Rr = cv::Matx33f::eye();
479
        cal.Tr = cv::Vec3f(0,0,0);
480
        cal.rot_axis_error = -1;
225 jakw 481
        return;
91 jakw 482
    }
225 jakw 483
 
484
    // Print to log
485
    std::stringstream out;
486
    out << "## Rotation Stage Calibration ##" << std::endl
487
        << "No. images used for calibration: " << qc0Stereo.size() << std::endl;
488
    cal.printRotationStage(out);
489
    out << std::endl << std::endl;
490
    emit logMessage(QString::fromStdString(out.str()));
491
 
492
    // Save to (reentrant) qsettings object
493
    settings.setValue("calibration/parameters", QVariant::fromValue(cal));
494
 
495
    emit done();
22 jakw 496
}