Subversion Repositories seema-scanner

Rev

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