Subversion Repositories seema-scanner

Rev

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