Subversion Repositories seema-scanner

Rev

Rev 141 | Rev 146 | Go to most recent revision | Details | Compare with Previous | Last modification | View Log | RSS feed

Rev Author Line No. Line
1 jakw 1
#include "cvtools.h"
2
 
3
#ifdef _WIN32
4
#include <cstdint>
5
#endif
6
 
7
#include <stdio.h>
8
 
141 jakw 9
#include <png.h>
10
#include <zlib.h>
11
 
1 jakw 12
namespace cvtools{
13
 
139 jakw 14
// Convert an BGR 3-channel image back into a Bayered image
15
void cvtColorBGRToBayerBG(const cv::Mat &imBGR, cv::Mat &imBayerBG){
16
 
17
    imBayerBG.create(imBGR.size(), CV_8UC1);
18
 
19
 
20
    for(int r=0; r<imBGR.rows; r++){
21
        for(int c=0; c<imBGR.cols; c++){
22
 
23
            bool evenRow = r % 2;
24
            bool evenCol = c % 2;
25
 
26
            if(evenRow & evenCol)
27
                imBayerBG.at<uchar>(r,c) = imBGR.at<cv::Vec3b>(r,c)[0];
28
            else if(!evenRow & !evenCol)
29
                imBayerBG.at<uchar>(r,c) = imBGR.at<cv::Vec3b>(r,c)[2];
30
            else
31
                imBayerBG.at<uchar>(r,c) = imBGR.at<cv::Vec3b>(r,c)[1];
32
 
33
        }
34
 
35
    }
36
 
37
 
38
}
39
 
40
 
121 jakw 41
// Removes matches not satisfying the epipolar constraint.
119 jakw 42
// F is the fundamental matrix.
121 jakw 43
// Works like cv::correctMatches(), except it removes matches with an error distance greater than maxD.
44
void removeIncorrectMatches(const cv::Mat F, const std::vector<cv::Point2f> &q0, const std::vector<cv::Point2f> &q1, const float maxD,
45
                                std::vector<cv::Point2f> q0Correct, std::vector<cv::Point2f> q1Correct){
119 jakw 46
 
121 jakw 47
    int n0 = (int)q0.size(), n1 = (int)q1.size();
48
    q0Correct.reserve(n0);
49
    q1Correct.reserve(n1);
119 jakw 50
 
51
    // Point to line distance
52
//    for( int i = 0; i < n1; i++ ){
121 jakw 53
//        cv::Vec3f p0 = cv::Vec3f(q0[i].x, q0[i].y, 1.0);
54
//        // Epipolar line defined by p0
55
//        cv::Vec3f l = F*p0;
119 jakw 56
//        l /= sqrt(l(0)*l(0) + l(1)*l(1));
57
//        for( int j = 0; j < n2; j++ ){
121 jakw 58
//            cv::Vec3f p1 = cv::Vec3f(q1[i].x, q1[i].y, 1.0);
119 jakw 59
//            // Signed distance to line
121 jakw 60
//            float d = l.dot(p1);
61
//            if(d < maxD){
62
//                q0Correct.push_back(q0[i]);
63
//                q1Correct.push_back(q1[i]);
64
//            }
119 jakw 65
//        }
66
//    }
67
 
68
    // Symmetric epipolar distance
121 jakw 69
    std::vector<cv::Point3f> l0, l1;
70
    cv::computeCorrespondEpilines(q0, 1, F, l0);
71
    cv::computeCorrespondEpilines(q1, 2, F, l1);
119 jakw 72
 
121 jakw 73
    for(int i = 0; i < n0; i++){
74
        cv::Vec3f p0 = cv::Vec3f(q0[i].x, q0[i].y, 1.0);
75
        for(int j = 0; j < n1; j++){
76
            cv::Vec3f p1 = cv::Vec3f(q1[j].x, q1[j].y, 1.0);
77
            float d01 = l0[i].dot(p1);
78
            float d10 = l1[j].dot(p0);
79
            float d = d01*d01 + d10*d10;
80
            if(d < maxD){
81
                q0Correct.push_back(q0[i]);
82
                q1Correct.push_back(q1[i]);
83
            }
119 jakw 84
        }
85
    }
86
 
87
//    // Sampson Error (H&Z, p. 287) (expensive...)
121 jakw 88
//    std::vector<cv::Point3f> p0, p1;
89
//    cv::convertPointsToHomogeneous(q0, p0);
119 jakw 90
//    cv::convertPointsToHomogeneous(q1, p1);
121 jakw 91
//    cv::Mat Fp0Mat = cv::Mat(F)*cv::Mat(p0).reshape(1).t();
92
//    cv::Mat FTp1Mat = cv::Mat(F.t())*cv::Mat(p1).reshape(1).t();
119 jakw 93
//    for( int i = 0; i < n1; i++ ){
121 jakw 94
//        cv::Vec3f Fp0 = Fp0Mat.col(i);
119 jakw 95
//        for( int j = 0; j < n2; j++ ){
121 jakw 96
//            cv::Vec3f FTp1 = FTp1Mat.col(j);
97
//            cv::Matx<float,1,1> p1TFp0 = cv::Matx31f(p1[j]).t()*F*cv::Matx31f(p0[i]);
98
//            float d = p1TFp0(0)*p1TFp0(0) / (Fp0(0)*Fp0(0) + Fp0(1)*Fp0(1) + FTp1(0)*FTp1(0) + FTp1(1)*FTp1(1));
99
//            if(d < maxD){
100
//                q0Correct.push_back(q0[i]);
101
//                q1Correct.push_back(q1[i]);
102
//            }
119 jakw 103
//        }
104
//    }
105
 
121 jakw 106
    return;
119 jakw 107
}
108
 
141 jakw 109
// Performs bitwise right-shift on every value of matrix I. This is done e.g. to remove the least significant bits in a 16 to 8-bit image conversion.
120 jakw 110
void rshift(cv::Mat& I, unsigned int shift){
111
 
112
    int nRows = I.rows;
113
    int nCols = I.cols;
114
 
115
    if (I.isContinuous()){
116
        nCols *= nRows;
117
        nRows = 1;
118
    }
119
 
120
    int i,j;
121
    unsigned short* p;
122
    for( i = 0; i < nRows; ++i){
123
        p = I.ptr<unsigned short>(i);
124
        for ( j = 0; j < nCols; ++j){
125
            p[j] = p[j]>>shift;
126
        }
127
    }
128
}
129
 
141 jakw 130
 
131
// Lightly modified OpenCV function which accepts a line width argument
132
void drawChessboardCorners(cv::InputOutputArray _image, cv::Size patternSize, cv::InputArray _corners, bool patternWasFound, int line_width){
133
    cv::Mat corners = _corners.getMat();
134
    if( corners.empty() )
135
        return;
136
    cv::Mat image = _image.getMat(); CvMat c_image = _image.getMat();
137
    int nelems = corners.checkVector(2, CV_32F, true);
138
    CV_Assert(nelems >= 0);
139
    cvtools::cvDrawChessboardCorners( &c_image, patternSize, (CvPoint2D32f*)corners.data,
140
                             nelems, patternWasFound, line_width);
141
}
142
 
143
 
144
 
50 jakw 145
void cvDrawChessboardCorners(CvArr* _image, CvSize pattern_size, CvPoint2D32f* corners, int count, int found, int line_width){
49 jakw 146
    const int shift = 0;
50 jakw 147
    const int radius = 12;
49 jakw 148
    const int r = radius*(1 << shift);
149
    int i;
150
    CvMat stub, *image;
151
    double scale = 1;
152
    int type, cn, line_type;
153
 
154
    image = cvGetMat( _image, &stub );
155
 
156
    type = CV_MAT_TYPE(image->type);
157
    cn = CV_MAT_CN(type);
158
    if( cn != 1 && cn != 3 && cn != 4 )
159
        CV_Error( CV_StsUnsupportedFormat, "Number of channels must be 1, 3 or 4" );
160
 
161
    switch( CV_MAT_DEPTH(image->type) )
162
    {
163
    case CV_8U:
164
        scale = 1;
165
        break;
166
    case CV_16U:
167
        scale = 256;
168
        break;
169
    case CV_32F:
170
        scale = 1./255;
171
        break;
172
    default:
173
        CV_Error( CV_StsUnsupportedFormat,
174
            "Only 8-bit, 16-bit or floating-point 32-bit images are supported" );
175
    }
176
 
177
    line_type = type == CV_8UC1 || type == CV_8UC3 ? CV_AA : 8;
178
 
179
    if( !found )
180
    {
181
        CvScalar color = {{0,0,255}};
182
        if( cn == 1 )
183
            color = cvScalarAll(200);
184
        color.val[0] *= scale;
185
        color.val[1] *= scale;
186
        color.val[2] *= scale;
187
        color.val[3] *= scale;
188
 
189
        for( i = 0; i < count; i++ )
190
        {
191
            CvPoint pt;
192
            pt.x = cvRound(corners[i].x*(1 << shift));
193
            pt.y = cvRound(corners[i].y*(1 << shift));
194
            cvLine( image, cvPoint( pt.x - r, pt.y - r ),
50 jakw 195
                    cvPoint( pt.x + r, pt.y + r ), color, line_width, line_type, shift );
49 jakw 196
            cvLine( image, cvPoint( pt.x - r, pt.y + r),
50 jakw 197
                    cvPoint( pt.x + r, pt.y - r), color, line_width, line_type, shift );
198
            cvCircle( image, pt, r+(1<<shift), color, line_width, line_type, shift );
49 jakw 199
        }
200
    }
201
    else
202
    {
203
        int x, y;
204
        CvPoint prev_pt = {0, 0};
205
        const int line_max = 7;
206
        static const CvScalar line_colors[line_max] =
207
        {
208
            {{0,0,255}},
209
            {{0,128,255}},
210
            {{0,200,200}},
211
            {{0,255,0}},
212
            {{200,200,0}},
213
            {{255,0,0}},
214
            {{255,0,255}}
215
        };
216
 
217
        for( y = 0, i = 0; y < pattern_size.height; y++ )
218
        {
219
            CvScalar color = line_colors[y % line_max];
220
            if( cn == 1 )
221
                color = cvScalarAll(200);
222
            color.val[0] *= scale;
223
            color.val[1] *= scale;
224
            color.val[2] *= scale;
225
            color.val[3] *= scale;
226
 
227
            for( x = 0; x < pattern_size.width; x++, i++ )
228
            {
229
                CvPoint pt;
230
                pt.x = cvRound(corners[i].x*(1 << shift));
231
                pt.y = cvRound(corners[i].y*(1 << shift));
232
 
233
                if( i != 0 )
234
                    cvLine( image, prev_pt, pt, color, 1, line_type, shift );
235
 
236
                cvLine( image, cvPoint(pt.x - r, pt.y - r),
50 jakw 237
                        cvPoint(pt.x + r, pt.y + r), color, line_width, line_type, shift );
49 jakw 238
                cvLine( image, cvPoint(pt.x - r, pt.y + r),
50 jakw 239
                        cvPoint(pt.x + r, pt.y - r), color, line_width, line_type, shift );
240
                cvCircle( image, pt, r+(1<<shift), color, line_width, line_type, shift );
49 jakw 241
                prev_pt = pt;
242
            }
243
        }
244
    }
245
}
246
 
74 jakw 247
// Returns the result of mod(mat(x,y), moduli) for each matrix element
248
cv::Mat modulo(const cv::Mat &mat, float n){
249
 
250
    cv::Mat ret(mat.rows, mat.cols, mat.type());
251
 
252
    for(int row=0; row<ret.rows; row++){
253
        for(int col=0; col<ret.cols; col++){
254
            float val = mat.at<float>(row, col);
255
            // note: std::fmod calculates the remainder, not arithmetic modulo
256
            ret.at<float>(row, col) = val - n * std::floor(val / n);
257
        }
258
    }
259
 
260
    return ret;
261
}
262
 
42 jakw 263
// Convert a 3xN matrix to a vector of Point3fs.
264
void matToPoints3f(const cv::Mat &mat, std::vector<cv::Point3f> &points){
265
 
266
    unsigned int nPoints = mat.cols;
267
    points.resize(nPoints);
268
 
269
    for(unsigned int i=0; i<nPoints; i++)
270
        points[i] = cv::Point3f(mat.at<float>(0, i), mat.at<float>(1, i), mat.at<float>(2, i));
271
}
272
 
273
// Convert a (Dim+1)xN matrix of homogenous points to a DimxN matrix of points in non-homogenous coordinates.
274
void convertMatFromHomogeneous(cv::Mat &src, cv::Mat &dst){
275
    unsigned int N = src.cols;
276
    unsigned int Dim = src.rows-1;
277
    dst.create(Dim, N, src.type());
278
    for(unsigned int i=0; i<N; i++){
279
        for(unsigned int j=0; j<Dim; j++)
280
            dst.at<float>(j,i) = src.at<float>(j,i)/src.at<float>(Dim,i);
281
    }
282
 
283
}
284
 
34 jakw 285
// Function to solve the hand-eye (or eye-in-hand) calibration problem.
286
// Finds [Omega | tau], to minimize ||[R_mark | t_mark][Omega | tau] - [Omega | tau][R | t]||^2
287
// Algorithm according to Tsai, Lenz, A new technique for fully autonomous and efficient 3d robotics hand-eye calibration
288
// DTU, 2014, Jakob Wilm
289
void handEyeCalibrationTsai(const std::vector<cv::Matx33f> R, const std::vector<cv::Vec3f> t, const std::vector<cv::Matx33f> R_mark, const std::vector<cv::Vec3f> t_mark, cv::Matx33f &Omega, cv::Vec3f &tau){
42 jakw 290
 
34 jakw 291
    int N = R.size();
292
    assert(N == R_mark.size());
293
    assert(N == t.size());
294
    assert(N == t_mark.size());
295
 
296
    // construct equations for rotation
297
    cv::Mat A(3*N, 3, CV_32F);
298
    cv::Mat b(3*N, 1, CV_32F);
299
    for(int i=0; i<N; i++){
300
        // angle axis representations
301
        cv::Vec3f rot;
302
        cv::Vec3f rot_mark;
303
        cv::Rodrigues(R[i], rot);
304
        cv::Rodrigues(R_mark[i], rot_mark);
305
 
306
        cv::Vec3f P = 2.0*sin(cv::norm(rot)/2.0)*cv::normalize(rot);
36 jakw 307
//std::cout << "P: " << std::endl << P << std::endl;
34 jakw 308
        cv::Vec3f P_mark = 2.0*sin(cv::norm(rot_mark)/2.0)*cv::normalize(rot_mark);
36 jakw 309
//std::cout << "P_mark: " << std::endl << P_mark << std::endl;
34 jakw 310
        cv::Vec3f sum = P+P_mark;
311
        cv::Mat crossProduct = (cv::Mat_<float>(3,3) << 0.0, -sum(2), sum(1), sum(2), 0.0, -sum(0), -sum(1), sum(0), 0.0);
36 jakw 312
//std::cout << "crossProduct: " << std::endl << crossProduct << std::endl;
34 jakw 313
        crossProduct.copyTo(A.rowRange(i*3, i*3+3));
314
 
315
        cv::Mat(P-P_mark).copyTo(b.rowRange(i*3, i*3+3));
316
    }
317
 
318
    // solve for rotation
36 jakw 319
    cv::Vec3f P_prime;
320
    cv::solve(A, b, P_prime, cv::DECOMP_SVD);
321
    cv::Vec3f P = 2.0*P_prime/(cv::sqrt(1.0 + cv::norm(P_prime)*cv::norm(P_prime)));
34 jakw 322
    float nP = cv::norm(P);
323
    cv::Mat crossProduct = (cv::Mat_<float>(3,3) << 0.0, -P(2), P(1), P(2), 0.0, -P(0), -P(1), P(0), 0.0);
324
    cv::Mat OmegaMat = (1.0-nP*nP/2.0)*cv::Mat::eye(3,3,CV_32F) + 0.5*(cv::Mat(P)*cv::Mat(P).t() + cv::sqrt(4.0 - nP*nP)*crossProduct);
325
    Omega = cv::Matx33f(OmegaMat);
326
 
327
    // construct equations for translation
328
    A.setTo(0.0);
329
    b.setTo(0.0);
330
    for(int i=0; i<N; i++){
331
 
36 jakw 332
        cv::Mat diff = cv::Mat(R_mark[i]) - cv::Mat::eye(3, 3, CV_32F);
34 jakw 333
        diff.copyTo(A.rowRange(i*3, i*3+3));
334
 
36 jakw 335
        cv::Mat diff_mark = cv::Mat(Omega*t[i] - t_mark[i]);
34 jakw 336
        diff_mark.copyTo(b.rowRange(i*3, i*3+3));
337
    }
338
 
339
    // solve for translation
36 jakw 340
    cv::solve(A, b, tau, cv::DECOMP_SVD);
81 jakw 341
 
342
    cv::Mat err_tau = b - (A*cv::Mat(tau));
343
    std::cout << err_tau << std::endl;
34 jakw 344
}
345
 
82 jakw 346
// Function to solve for the rotation axis from sets of 3D point coordinates of flat pattern feature points
347
// Algorithm according to Chen et al., Rotation axis calibration of a turntable using constrained global optimization, Optik 2014
348
// DTU, 2014, Jakob Wilm
349
void rotationAxisCalibration(const std::vector< std::vector<cv::Point3f> > Qcam, const std::vector<cv::Point3f> Qobj, cv::Vec3f &axis, cv::Vec3f &point){
350
 
351
    // number of frames (points on each arch)
352
    int l = Qcam.size();
353
 
354
    // number of points in each frame
355
    int mn = Qobj.size();
356
 
357
    assert(mn == Qcam[0].size());
358
 
359
    // construct matrix for axis determination
360
    cv::Mat M(6, 6, CV_32F, cv::Scalar(0));
361
 
362
    for(int k=0; k<l; k++){
363
        for(int idx=0; idx<mn; idx++){
364
 
83 jakw 365
//            float i = Qobj[idx].x+4;
366
//            float j = Qobj[idx].y+4;
367
            float i = Qobj[idx].x;
368
            float j = Qobj[idx].y;
82 jakw 369
 
370
            float x = Qcam[k][idx].x;
371
            float y = Qcam[k][idx].y;
372
            float z = Qcam[k][idx].z;
373
 
374
            M += (cv::Mat_<float>(6,6) << x*x, x*y, x*z, x, i*x, j*x,
375
                                            0, y*y, y*z, y, i*y, j*y,
376
                                            0,   0, z*z, z, i*z, j*z,
377
                                            0,   0,   0, 1,   i,   j,
378
                                            0,   0,   0, 0, i*i, i*j,
379
                                            0,   0,   0, 0,   0, j*j);
380
 
381
        }
382
    }
91 jakw 383
 
82 jakw 384
    cv::completeSymm(M, false);
91 jakw 385
 
82 jakw 386
    // solve for axis
387
    std::vector<float> lambda;
388
    cv::Mat u;
389
    cv::eigen(M, lambda, u);
390
 
391
    float minLambda = abs(lambda[0]);
392
    int idx = 0;
393
    for(int i=1; i<lambda.size(); i++){
394
        if(abs(lambda[i]) < minLambda){
395
            minLambda = lambda[i];
396
            idx = i;
397
        }
398
    }
399
 
400
    axis = u.row(idx).colRange(0, 3);
91 jakw 401
    axis = cv::normalize(axis);
82 jakw 402
 
83 jakw 403
    float nx = u.at<float>(idx, 0);
404
    float ny = u.at<float>(idx, 1);
405
    float nz = u.at<float>(idx, 2);
406
    float d  = u.at<float>(idx, 3);
407
    float dh = u.at<float>(idx, 4);
408
    float dv = u.at<float>(idx, 5);
82 jakw 409
 
90 jakw 410
//    // Paper version: c is initially eliminated
411
//    cv::Mat A(l*mn, mn+2, CV_32F, cv::Scalar(0.0));
412
//    cv::Mat bb(l*mn, 1, CV_32F);
413
 
414
//    for(int k=0; k<l; k++){
415
//        for(int idx=0; idx<mn; idx++){
416
 
417
//            float i = Qobj[idx].x;
418
//            float j = Qobj[idx].y;
419
 
420
//            float x = Qcam[k][idx].x;
421
//            float y = Qcam[k][idx].y;
422
//            float z = Qcam[k][idx].z;
423
 
424
//            float f = x*x + y*y + z*z + (2*x*nx + 2*y*ny + 2*z*nz)*(i*dh + j*dv);
425
 
426
//            int row = k*mn+idx;
427
//            A.at<float>(row, 0) = 2*x - (2*z*nx)/nz;
428
//            A.at<float>(row, 1) = 2*y - (2*z*ny)/nz;
429
//            A.at<float>(row, idx+2) = 1.0;
430
 
431
//            bb.at<float>(row, 0) = f + (2*z*d)/nz;
432
//        }
433
//    }
434
 
435
//    // solve for point
436
//    cv::Mat abe;
437
//    cv::solve(A, bb, abe, cv::DECOMP_SVD);
438
 
439
//    float a = abe.at<float>(0, 0);
440
//    float b = abe.at<float>(1, 0);
441
//    float c = -(nx*a+ny*b+d)/nz;
442
 
443
    // Our version: solve simultanously for a,b,c
444
    cv::Mat A(l*mn, mn+3, CV_32F, cv::Scalar(0.0));
83 jakw 445
    cv::Mat bb(l*mn, 1, CV_32F);
82 jakw 446
 
447
    for(int k=0; k<l; k++){
448
        for(int idx=0; idx<mn; idx++){
449
 
450
            float i = Qobj[idx].x;
451
            float j = Qobj[idx].y;
452
 
453
            float x = Qcam[k][idx].x;
454
            float y = Qcam[k][idx].y;
455
            float z = Qcam[k][idx].z;
456
 
457
            float f = x*x + y*y + z*z + (2*x*nx + 2*y*ny + 2*z*nz)*(i*dh + j*dv);
458
 
459
            int row = k*mn+idx;
90 jakw 460
            A.at<float>(row, 0) = 2*x;
461
            A.at<float>(row, 1) = 2*y;
462
            A.at<float>(row, 2) = 2*z;
463
            A.at<float>(row, idx+3) = 1.0;
82 jakw 464
 
90 jakw 465
            bb.at<float>(row, 0) = f;
82 jakw 466
        }
467
    }
468
 
469
    // solve for point
470
    cv::Mat abe;
83 jakw 471
    cv::solve(A, bb, abe, cv::DECOMP_SVD);
82 jakw 472
 
83 jakw 473
    float a = abe.at<float>(0, 0);
474
    float b = abe.at<float>(1, 0);
90 jakw 475
    float c = abe.at<float>(2, 0);
82 jakw 476
 
83 jakw 477
    point[0] = a;
478
    point[1] = b;
479
    point[2] = c;
480
 
82 jakw 481
}
482
 
34 jakw 483
// Function to fit two sets of corresponding pose data.
484
// Finds [Omega | tau], to minimize ||[R_mark | t_mark] - [Omega | tau][R | t]||^2
31 jakw 485
// Algorithm and notation according to Mili Shah, Comparing two sets of corresponding six degree of freedom data, CVIU 2011.
486
// DTU, 2013, Oline V. Olesen, Jakob Wilm
487
void fitSixDofData(const std::vector<cv::Matx33f> R, const std::vector<cv::Vec3f> t, const std::vector<cv::Matx33f> R_mark, const std::vector<cv::Vec3f> t_mark, cv::Matx33f &Omega, cv::Vec3f &tau){
34 jakw 488
 
31 jakw 489
    int N = R.size();
490
    assert(N == R_mark.size());
491
    assert(N == t.size());
492
    assert(N == t_mark.size());
493
 
494
    // Mean translations
495
    cv::Vec3f t_mean;
496
    cv::Vec3f t_mark_mean;
497
    for(int i=0; i<N; i++){
498
        t_mean += 1.0/N * t[i];
499
        t_mark_mean += 1.0/N * t_mark[i];
500
    }
501
 
502
    // Data with mean adjusted translations
503
    cv::Mat X_bar(3, 4*N, CV_32F);
504
    cv::Mat X_mark_bar(3, 4*N, CV_32F);
505
    for(int i=0; i<N; i++){
33 jakw 506
        cv::Mat(R[i]).copyTo(X_bar.colRange(i*4,i*4+3));
507
        cv::Mat(t[i] - t_mean).copyTo(X_bar.col(i*4+3));
508
        cv::Mat(R_mark[i]).copyTo(X_mark_bar.colRange(i*4,i*4+3));
509
        cv::Mat(t_mark[i] - t_mark_mean).copyTo(X_mark_bar.col(i*4+3));
31 jakw 510
    }
33 jakw 511
    //std::cout << X_bar << std::endl;
31 jakw 512
    // SVD
33 jakw 513
    cv::Mat W, U, VT;
31 jakw 514
    cv::SVDecomp(X_bar*X_mark_bar.t(), W, U, VT);
515
 
516
    cv::Matx33f D = cv::Matx33f::eye();
517
    if(cv::determinant(VT*U) < 0)
518
        D(3,3) = -1;
519
 
520
    // Best rotation
33 jakw 521
    Omega = cv::Matx33f(cv::Mat(VT.t()))*D*cv::Matx33f(cv::Mat(U.t()));
31 jakw 522
 
523
    // Best translation
524
    tau = t_mark_mean - Omega*t_mean;
525
 
526
}
527
 
1 jakw 528
// Forward distortion of points. The inverse of the undistortion in cv::initUndistortRectifyMap().
529
// Inspired by Pascal Thomet, http://code.opencv.org/issues/1387#note-11
530
// Convention for distortion parameters: http://www.vision.caltech.edu/bouguetj/calib_doc/htmls/parameters.html
531
void initDistortMap(const cv::Matx33f cameraMatrix, const cv::Vec<float, 5> distCoeffs, const cv::Size size, cv::Mat &map1, cv::Mat &map2){
532
 
533
    float fx = cameraMatrix(0,0);
534
    float fy = cameraMatrix(1,1);
535
    float ux = cameraMatrix(0,2);
536
    float uy = cameraMatrix(1,2);
537
 
538
    float k1 = distCoeffs[0];
539
    float k2 = distCoeffs[1];
540
    float p1 = distCoeffs[2];
541
    float p2 = distCoeffs[3];
542
    float k3 = distCoeffs[4];
543
 
544
    map1.create(size, CV_32F);
545
    map2.create(size, CV_32F);
546
 
547
    for(int col = 0; col < size.width; col++){
548
        for(int row = 0; row < size.height; row++){
549
 
550
            // move origo to principal point and convert using focal length
551
            float x = (col-ux)/fx;
552
            float y = (row-uy)/fy;
553
 
554
            float xCorrected, yCorrected;
555
 
556
            //Step 1 : correct distortion
557
            float r2 = x*x + y*y;
558
            //radial
559
            xCorrected = x * (1. + k1*r2 + k2*r2*r2 + k3*r2*r2*r2);
560
            yCorrected = y * (1. + k1*r2 + k2*r2*r2 + k3*r2*r2*r2);
561
            //tangential
562
            xCorrected = xCorrected + (2.*p1*x*y + p2*(r2+2.*x*x));
563
            yCorrected = yCorrected + (p1*(r2+2.*y*y) + 2.*p2*x*y);
564
 
565
            //convert back to pixel coordinates
566
            float col_displaced = xCorrected * fx + ux;
567
            float row_displaced = yCorrected * fy + uy;
568
 
569
            // correct the vector in the opposite direction
570
            map1.at<float>(row,col) = col+(col-col_displaced);
571
            map2.at<float>(row,col) = row +(row-row_displaced);
572
        }
573
    }
574
}
575
 
576
// Downsample a texture which was created in virtual column/row space for a diamond pixel array projector
577
cv::Mat diamondDownsample(cv::Mat &pattern){
578
 
579
    cv::Mat pattern_diamond(pattern.rows,pattern.cols/2,CV_8UC3);
580
 
581
    for(unsigned int col = 0; col < pattern_diamond.cols; col++){
582
        for(unsigned int row = 0; row < pattern_diamond.rows; row++){
583
 
584
            pattern_diamond.at<cv::Vec3b>(row,col)=pattern.at<cv::Vec3b>(row,col*2+row%2);
585
        }
586
    }
587
 
588
    return pattern_diamond;
589
 
590
}
591
 
592
 
593
void mouseCallback(int evt, int x, int y, int flags, void* param){
594
    cv::Mat *im = (cv::Mat*) param;
595
    if (evt == CV_EVENT_LBUTTONDOWN) {
596
        if(im->type() == CV_8UC3){
597
            printf("%d %d: %d, %d, %d\n",
598
                   x, y,
599
                   (int)(*im).at<cv::Vec3b>(y, x)[0],
600
                    (int)(*im).at<cv::Vec3b>(y, x)[1],
601
                    (int)(*im).at<cv::Vec3b>(y, x)[2]);
602
        } else if (im->type() == CV_32F) {
603
            printf("%d %d: %f\n",
604
                   x, y,
605
                   im->at<float>(y, x));
606
        }
607
    }
608
}
609
 
610
void imshow(const char *windowName, cv::Mat im, unsigned int x, unsigned int y){
611
 
612
    // Imshow
613
    if(!cvGetWindowHandle(windowName)){
614
        int windowFlags = CV_GUI_EXPANDED | CV_WINDOW_KEEPRATIO;
615
        cv::namedWindow(windowName, windowFlags);
616
        cv::moveWindow(windowName, x, y);
617
    }
618
    cv::imshow(windowName, im);
619
}
620
 
621
void imagesc(const char *windowName, cv::Mat im){
622
 
623
    // Imshow with scaled image
624
 
625
 
626
}
627
 
628
cv::Mat histimage(cv::Mat histogram){
629
 
630
    cv::Mat histImage(512, 640, CV_8UC3, cv::Scalar(0));
631
 
632
    // Normalize the result to [ 2, histImage.rows-2 ]
633
    cv::normalize(histogram, histogram, 2, histImage.rows-2, cv::NORM_MINMAX, -1, cv::Mat());
634
 
635
    float bin_w = (float)histImage.cols/(float)histogram.rows;
636
 
637
    // Draw main histogram
638
    for(int i = 1; i < histogram.rows-10; i++){
639
        cv::line(histImage, cv::Point( bin_w*(i-1), histImage.rows - cvRound(histogram.at<float>(i-1)) ),
640
                 cv::Point( bin_w*(i), histImage.rows - cvRound(histogram.at<float>(i)) ),
641
                 cv::Scalar(255, 255, 255), 2, 4);
642
    }
643
 
644
    // Draw red max
645
    for(int i = histogram.rows-10; i < histogram.rows; i++){
646
        cv::line(histImage, cv::Point( bin_w*(i-1), histImage.rows - cvRound(histogram.at<float>(i-1)) ),
647
                 cv::Point( bin_w*(i), histImage.rows - cvRound(histogram.at<float>(i)) ),
648
                 cv::Scalar(0, 0, 255), 2, 4);
649
    }
650
 
651
    return histImage;
652
}
653
 
654
void hist(const char *windowName, cv::Mat histogram, unsigned int x, unsigned int y){
655
 
656
    // Display
657
    imshow(windowName, histimage(histogram), x, y);
658
    cv::Point(1,2);
659
}
660
 
661
 
662
void writeMat(cv::Mat const& mat, const char* filename, const char* varName, bool bgr2rgb){
663
    /*!
664
         *  \author Philip G. Lee <rocketman768@gmail.com>
665
         *  Write \b mat into \b filename
666
         *  in uncompressed .mat format (Level 5 MATLAB) for Matlab.
667
         *  The variable name in matlab will be \b varName. If
668
         *  \b bgr2rgb is true and there are 3 channels, swaps 1st and 3rd
669
         *  channels in the output. This is needed because OpenCV matrices
670
         *  are bgr, while Matlab is rgb. This has been tested to work with
671
         *  3-channel single-precision floating point matrices, and I hope
672
         *  it works on other types/channels, but not exactly sure.
673
         *  Documentation at <http://www.mathworks.com/help/pdf_doc/matlab/matfile_format.pdf>
674
         */
675
    int textLen = 116;
676
    char* text;
677
    int subsysOffsetLen = 8;
678
    char* subsysOffset;
679
    int verLen = 2;
680
    char* ver;
681
    char flags;
682
    int bytes;
683
    int padBytes;
684
    int bytesPerElement;
685
    int i,j,k,k2;
686
    bool doBgrSwap;
687
    char mxClass;
688
    int32_t miClass;
689
    uchar const* rowPtr;
690
    uint32_t tmp32;
691
    float tmp;
692
    FILE* fp;
693
 
694
    // Matlab constants.
695
    const uint16_t MI = 0x4d49; // Contains "MI" in ascii.
696
    const int32_t miINT8 = 1;
697
    const int32_t miUINT8 = 2;
698
    const int32_t miINT16 = 3;
699
    const int32_t miUINT16 = 4;
700
    const int32_t miINT32 = 5;
701
    const int32_t miUINT32 = 6;
702
    const int32_t miSINGLE = 7;
703
    const int32_t miDOUBLE = 9;
704
    const int32_t miMATRIX = 14;
705
    const char mxDOUBLE_CLASS = 6;
706
    const char mxSINGLE_CLASS = 7;
707
    const char mxINT8_CLASS = 8;
708
    const char mxUINT8_CLASS = 9;
709
    const char mxINT16_CLASS = 10;
710
    const char mxUINT16_CLASS = 11;
711
    const char mxINT32_CLASS = 12;
712
    const char mxUINT32_CLASS = 13;
713
    const uint64_t zero = 0; // Used for padding.
714
 
715
    fp = fopen( filename, "wb" );
716
 
717
    if( fp == 0 )
718
        return;
719
 
720
    const int rows = mat.rows;
721
    const int cols = mat.cols;
722
    const int chans = mat.channels();
723
 
724
    doBgrSwap = (chans==3) && bgr2rgb;
725
 
726
    // I hope this mapping is right :-/
727
    switch( mat.depth() ){
728
    case CV_8U:
729
        mxClass = mxUINT8_CLASS;
730
        miClass = miUINT8;
731
        bytesPerElement = 1;
732
        break;
733
    case CV_8S:
734
        mxClass = mxINT8_CLASS;
735
        miClass = miINT8;
736
        bytesPerElement = 1;
737
        break;
738
    case CV_16U:
739
        mxClass = mxUINT16_CLASS;
740
        miClass = miUINT16;
741
        bytesPerElement = 2;
742
        break;
743
    case CV_16S:
744
        mxClass = mxINT16_CLASS;
745
        miClass = miINT16;
746
        bytesPerElement = 2;
747
        break;
748
    case CV_32S:
749
        mxClass = mxINT32_CLASS;
750
        miClass = miINT32;
751
        bytesPerElement = 4;
752
        break;
753
    case CV_32F:
754
        mxClass = mxSINGLE_CLASS;
755
        miClass = miSINGLE;
756
        bytesPerElement = 4;
757
        break;
758
    case CV_64F:
759
        mxClass = mxDOUBLE_CLASS;
760
        miClass = miDOUBLE;
761
        bytesPerElement = 8;
762
        break;
763
    default:
764
        return;
765
    }
766
 
767
    //==================Mat-file header (128 bytes, page 1-5)==================
768
    text = new char[textLen]; // Human-readable text.
769
    memset( text, ' ', textLen );
770
    text[textLen-1] = '\0';
771
    const char* t = "MATLAB 5.0 MAT-file, Platform: PCWIN";
772
    memcpy( text, t, strlen(t) );
773
 
774
    subsysOffset = new char[subsysOffsetLen]; // Zeros for us.
775
    memset( subsysOffset, 0x00, subsysOffsetLen );
776
    ver = new char[verLen];
777
    ver[0] = 0x00;
778
    ver[1] = 0x01;
779
 
780
    fwrite( text, 1, textLen, fp );
781
    fwrite( subsysOffset, 1, subsysOffsetLen, fp );
782
    fwrite( ver, 1, verLen, fp );
783
    // Endian indicator. MI will show up as "MI" on big-endian
784
    // systems and "IM" on little-endian systems.
785
    fwrite( &MI, 2, 1, fp );
786
    //+++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++
787
 
788
    //===================Data element tag (8 bytes, page 1-8)==================
789
    bytes = 16 + 24 + (8 + strlen(varName) + (8-(strlen(varName)%8))%8)
790
            + (8 + rows*cols*chans*bytesPerElement);
791
    fwrite( &miMATRIX, 4, 1, fp ); // Data type.
792
    fwrite( &bytes, 4, 1, fp); // Data size in bytes.
793
    //+++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++
794
 
795
    //====================Array flags (16 bytes, page 1-15)====================
796
    bytes = 8;
797
    fwrite( &miUINT32, 4, 1, fp );
798
    fwrite( &bytes, 4, 1, fp );
799
    flags = 0x00; // Complex, logical, and global flags all off.
800
 
801
    tmp32 = 0;
802
    tmp32 = (flags << 8 ) | (mxClass);
803
    fwrite( &tmp32, 4, 1, fp );
804
 
805
    fwrite( &zero, 4, 1, fp ); // Padding to 64-bit boundary.
806
    //+++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++
807
 
808
    //===============Dimensions subelement (24 bytes, page 1-17)===============
809
    bytes = 12;
810
    fwrite( &miINT32, 4, 1, fp );
811
    fwrite( &bytes, 4, 1, fp );
812
 
813
    fwrite( &rows, 4, 1, fp );
814
    fwrite( &cols, 4, 1, fp );
815
    fwrite( &chans, 4, 1, fp );
816
    fwrite( &zero, 4, 1, fp ); // Padding to 64-bit boundary.
817
    //+++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++
818
 
819
    //==Array name (8 + strlen(varName) + (8-(strlen(varName)%8))%8 bytes, page 1-17)==
820
    bytes = strlen(varName);
821
 
822
    fwrite( &miINT8, 4, 1, fp );
823
    fwrite( &bytes, 4, 1, fp );
824
    fwrite( varName, 1, bytes, fp );
825
 
826
    // Pad to nearest 64-bit boundary.
827
    padBytes = (8-(bytes%8))%8;
828
    fwrite( &zero, 1, padBytes, fp );
829
    //+++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++
830
 
831
    //====Matrix data (rows*cols*chans*bytesPerElement+8 bytes, page 1-20)=====
832
    bytes = rows*cols*chans*bytesPerElement;
833
    fwrite( &miClass, 4, 1, fp );
834
    fwrite( &bytes, 4, 1, fp );
835
 
836
    for( k = 0; k < chans; ++k )
837
    {
838
        if( doBgrSwap )
839
        {
840
            k2 = (k==0)? 2 : ((k==2)? 0 : 1);
841
        }
842
        else
843
            k2 = k;
844
 
845
        for( j = 0; j < cols; ++j )
846
        {
847
            for( i = 0; i < rows; ++i )
848
            {
849
                rowPtr = mat.data + mat.step*i;
850
                fwrite( rowPtr + (chans*j + k2)*bytesPerElement, bytesPerElement, 1, fp );
851
            }
852
        }
853
    }
854
 
855
    // Pad to 64-bit boundary.
856
    padBytes = (8-(bytes%8))%8;
857
    fwrite( &zero, 1, padBytes, fp );
858
    //+++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++
859
 
860
    fclose(fp);
861
    delete[] text;
862
    delete[] subsysOffset;
863
    delete[] ver;
864
}
865
 
866
 
867
 
868
 
869
 
870
}