Subversion Repositories seema-scanner

Rev

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