Subversion Repositories seema-scanner

Rev

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