Subversion Repositories seema-scanner

Rev

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