Subversion Repositories seema-scanner

Rev

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