Subversion Repositories seema-scanner

Rev

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