summaryrefslogtreecommitdiff
path: root/src/vision.cpp
blob: 0f89b358361df24c70e6661103982d0bf14bc2aa (plain)
1
2
3
4
5
6
7
8
9
10
11
12
13
14
15
16
17
18
19
20
21
22
23
24
25
26
27
28
29
30
31
32
33
34
35
36
37
38
39
40
41
42
43
44
45
46
47
48
49
50
51
52
53
54
55
56
57
58
59
60
61
62
63
64
65
66
67
68
69
70
71
72
73
74
75
76
77
78
79
80
81
82
83
84
85
86
87
88
89
90
91
92
93
94
95
96
97
98
99
100
101
102
103
104
105
106
107
108
109
110
111
112
113
114
115
116
117
118
119
120
121
122
123
124
125
126
127
128
129
130
131
132
133
134
135
136
137
138
139
140
141
142
143
144
145
146
147
148
149
150
151
152
153
154
155
156
157
158
159
160
161
162
163
164
165
166
167
168
169
170
171
172
173
174
175
176
177
178
179
180
181
182
183
184
185
186
187
188
189
190
191
192
193
194
195
196
197
198
199
200
201
202
203
204
205
206
207
208
209
210
211
212
213
214
215
216
217
218
219
220
221
222
223
224
225
226
227
228
229
230
231
232
233
234
235
236
237
238
239
240
241
242
243
244
245
246
247
248
249
250
251
252
253
254
255
256
257
258
259
260
261
262
263
264
265
266
267
268
269
270
271
272
273
274
275
276
277
278
279
280
281
282
283
284
285
286
287
288
289
290
291
292
293
294
295
296
297
298
299
300
301
302
303
304
305
306
307
308
309
310
311
312
/*
 * =====================================================================================
 *
 *       Filename:  vision.cpp
 *
 *    Description:  Class for vision tasks such as opening images, plotting
 *    points in the image frame, performing measurements.
 *
 *        Version:  1.0
 *        Created:  04/07/2017 11:34:16 AM
 *       Revision:  none
 *       Compiler:  gcc
 *
 *         Author:  Martin Miller (MHM), miller7@illinois.edu
 *   Organization:  Aerospace Robotics and Controls Lab (ARC)
 *
 * =====================================================================================
 */
#include "vision.h"


/*
 *--------------------------------------------------------------------------------------
 *       Class:  Vision
 *      Method:  Vision
 * Description:  constructor
 *--------------------------------------------------------------------------------------
 */
Vision::Vision ()
{
    ;
}  /* -----  end of method Vision::Vision  (constructor)  ----- */

/*
 *--------------------------------------------------------------------------------------
 *       Class:  Vision
 *      Method:  Vision :: open
 * Description:  Opens the given image, undistorts.
 *--------------------------------------------------------------------------------------
 */
void
Vision::open ( const char *fn, const Camera &cam )
{
    Mat bayered, unbayered ;
    bayered = cv::imread(fn, -1);
    if (!bayered.data) {
        fprintf(stderr, "Could not read %s.\n", fn);
        exit(1);
    }
    cv::cvtColor(bayered, unbayered, CV_BayerBG2BGR ,3);
    unbayered.convertTo(original, CV_32FC3);
    Mat luv;
    cv::cvtColor(original, gray, CV_BGR2GRAY);
    //vector<Mat> luv_channels;
    //cv::split(luv,luv_channels);
    //gray = luv_channels[0];
    display = unbayered.clone();
    return ;
}		/* -----  end of method Vision::open  ----- */

/*
 *--------------------------------------------------------------------------------------
 *       Class:  Vision
 *      Method:  Vision :: drawMeasurements
 * Description:  Draws the measured points onto the image.
 *--------------------------------------------------------------------------------------
 */
void
Vision::drawMeasurements ( const vector<measurement_t> &z, const Camera &cam,
        const cv::Scalar &colsrc, const cv::Scalar &colref, bool drawEllipse)
{
    cv::Scalar ellcol(0,0,200);
    for (auto i=z.begin(); i!=z.end(); ++i) {
        if (i->z_type==HEIGHT) continue;
        Vector3d xis, xir;
        xis = cam.body2img(i->source);
        xis /= xis[2];
        xir = cam.body2img(i->reflection);
        xir /= xir[2];
        cv::Point ps(xis[0],xis[1]);
        cv::Point pr(xir[0],xir[1]);

        cv::circle(display, ps, 3, colsrc,2);
        cv::circle(display, pr, 3, colref);

        if (drawEllipse) {
            double xs, ys, xr, yr;
            xs = 2*sqrt(i->Ssrc(0));
            ys = 2*sqrt(i->Ssrc(1));
            xr = 2*sqrt(i->Sref(0));
            yr = 2*sqrt(i->Sref(1));
            
            // Create rotated rect for ellipse
            cv::RotatedRect rrs(ps, cv::Size(2*INLIER_THRESHOLD*xs, 2*INLIER_THRESHOLD*ys), 0.);
            cv::RotatedRect rrr(pr, cv::Size(2*INLIER_THRESHOLD*xr, 2*INLIER_THRESHOLD*yr), 0.);
            try {
                cv::ellipse(display, rrs, ellcol );
                cv::ellipse(display, rrr, ellcol);
            } catch (...) {
                cerr << "caught and error drawing ellipse" << endl;
            }
        }
    }
    return ;
}		/* -----  end of method Vision::drawMeasurements  ----- */

/*
 *--------------------------------------------------------------------------------------
 *       Class:  Vision
 *      Method:  Vision :: show
 * Description:  Show the display image.
 *--------------------------------------------------------------------------------------
 */
void
Vision::show (  )
{
    cv::imshow("Image view", display);
    cv::waitKey(1);
    return ;
}		/* -----  end of method Vision::show  ----- */

/*
 *--------------------------------------------------------------------------------------
 *       Class:  Vision
 *      Method:  Vision :: acquireFeatures
 * Description:  Finds new features, assigns IDs, extracts descriptors.
 *--------------------------------------------------------------------------------------
 */
void
Vision::acquireFeatures ( const Camera &cam, vector<measurement_t> &z )
{
    vector<cv::Point2f> corners;

    Mat mask = Mat::zeros(gray.size(),CV_8UC1);
    cv::Rect roi(50,50,gray.cols-100, gray.rows-100);
    mask(roi) = 255*Mat::ones(roi.size(),CV_8UC1);

    cv::goodFeaturesToTrack(gray, corners, 50, 0.1, 20, mask);
    for (auto i=corners.begin(); i!=corners.end(); ++i) {
        measurement_t m;
        m.id = _id++;
        m.z_type = MONO;
        Vector3d xi;
        xi << i->x, i->y, 1.;
        m.source = cam.img2body(xi);
        m.reflection << 0,0,1;
        getTemplate(m.patch,xi);
        if (m.patch.cols==0 || m.patch.rows==0) continue;
        z.push_back(m);
    }
    return ;
}		/* -----  end of method Vision::acquireFeatures  ----- */

void
Vision::getTemplate( Mat &p, const Vector3d &pt)
{
    cv::Rect imrect(0,0,gray.cols,gray.rows);
    assert (PATCHSIZE%2==1); // patch size must be odd
    cv::Point pti;
    pti.x = (int) pt(0);
    pti.y = (int)pt(1);
    cv::Point topLeft = pti - cv::Point(PATCHSIZE/2,PATCHSIZE/2);
    cv::Size sz(PATCHSIZE,PATCHSIZE);
    cv::Rect roi(topLeft, sz);
    roi &= imrect;
    p = gray(roi).clone();
}

void
Vision::measurements ( const Camera &cam, const vector<measurement_t> &zin,
        vector<measurement_t> &zout)
{
    for (auto i=zin.begin(); i!=zin.end(); ++i) {
        measurement_t z;
        z = *i;
        if (i->z_type==MONO || i->z_type==BOTH) {
            measurement_t zins, zouts;
            zins = *i;
            zins.z_type = MONO;
            measure(cam,zins, zouts);
            z.xcorrmax = zouts.xcorrmax;
            z.source = zouts.source;
        }
        if (i->z_type==REFLECTION || i->z_type==BOTH) {
            measurement_t zinr, zoutr;
            zinr = *i;
            zinr.z_type = REFLECTION;
            measure(cam, zinr, zoutr);
            z.reflection = zoutr.reflection;
        }
        if (z.xcorrmax>0.90)
            zout.push_back(z);
    }
    return ;
}		/* -----  end of method Vision::measurements  ----- */

/*
 *--------------------------------------------------------------------------------------
 *       Class:  Vision
 *      Method:  Vision :: measure
 * Description:  Performs a measurement on zin and stores it in zout.
 *--------------------------------------------------------------------------------------
 */
void
Vision::measure ( const Camera &cam, const measurement_t &zin, measurement_t &zout )
{
    assert((zin.z_type==MONO) || (zin.z_type==REFLECTION));
    // Create ROIs
    RotatedRect searchrr; // Rotated rect describing search ellipse
    Rect searchr; // Rect describing search ellipse
    searchRegion(cam, zin, searchrr);
    searchr = searchrr.boundingRect();

    // Add margin around search region
    Rect imrect(cv::Point(0,0), gray.size());
    cv::Point offset(PATCHSIZE/2,PATCHSIZE/2);
    cv::Size enlarge(2*(PATCHSIZE/2),2*(PATCHSIZE/2));
    Rect roi = (searchr-offset) + enlarge;
    if ((roi & imrect)==roi) {
        Mat sr = gray(roi);

        // Match template
        Mat result;
        result.create( sr.cols-zin.patch.cols+1, sr.rows-zin.patch.rows+1, CV_32FC1 );
        if (zin.z_type==MONO) {
            matchTemplate( sr, zin.patch, result, CV_TM_CCOEFF_NORMED);
        } else {
            matchTemplate( sr, zin.refpatch, result, CV_TM_CCOEFF_NORMED);
        }

        // Mask the ellipse around the result.
        Mat mask = Mat::zeros(result.size(), CV_8UC1);
        RotatedRect ellipserr;
        cv::Size sz = searchr.size();
        ellipserr.size = sz;
        ellipserr.center = cv::Point2f(0.5*sz.width,0.5*sz.height);
        ellipserr.angle = 0;
        cv::ellipse(mask, ellipserr, cv::Scalar(255), -1 );
        double minval, maxval;
        int minidx[2], maxidx[2];
        cv::minMaxIdx(result, &minval, &maxval, minidx, maxidx, mask);
        cv::Point maxpt(maxidx[1], maxidx[0]);

        cv::Point zpi = maxpt+searchr.tl();
        Vector3d zi;
        zi << zpi.x, zpi.y, 1;

        zout.id = zin.id;
        if (zin.z_type==MONO) {
            zout.source = cam.img2body(zi);
            zout.z_type = MONO;
        } else {
            zout.reflection = cam.img2body(zi);
            zout.z_type = REFLECTION;
        }
        zout.xcorrmax = maxval;

        /*
        Mat sr8, patch8, rpatch8;
        sr.convertTo(sr8, CV_8UC1);
        zin.patch.convertTo(patch8, CV_8UC1);
        zin.refpatch.convertTo(rpatch8, CV_8UC1);
        cv::circle(sr8, maxpt+offset, 4, cv::Scalar(255), 1);
        cv::Point spt(PATCHSIZE/2, PATCHSIZE/2);
        cv::circle(patch8, spt, 4, cv::Scalar(255), 1);
        cv::circle(display, maxpt+searchr.tl(), 4, cv::Scalar(20,240,0),2);
        cv::imshow("s region", sr8);
        cv::imshow("patch", patch8);
        cv::imshow("rpatch", rpatch8);
        cv::imshow("result", result);
        cv::imshow("mask", mask);
        cv::imshow("display2", display);
        cerr << maxval << endl;
        cv::waitKey(0);
        */
    } else {
        zout.xcorrmax = -1.;
    }
    return ;
}		/* -----  end of method Vision::measure  ----- */

void
Vision::searchRegion ( const Camera &cam, const measurement_t &z, cv::RotatedRect &rr )
{
    assert((z.z_type==MONO) || (z.z_type==REFLECTION));
    Vector3d xis;
    if (z.z_type==MONO) {
        xis = cam.body2img(z.source);
    } else {
        xis = cam.body2img(z.source);
    }
    //xis /= xis[2];
    cv::Point ps;
    ps.x = xis[0];
    ps.y = xis[1];

    double xs, ys;
    if (z.z_type==MONO) {
        xs = 2*sqrt(z.Ssrc(0));
        ys = 2*sqrt(z.Ssrc(1));
    } else {
        xs = 2*sqrt(z.Sref(0));
        ys = 2*sqrt(z.Sref(1));
    }
    
    // Create rotated rect for ellipse
    rr = cv::RotatedRect(ps, cv::Size(2*INLIER_THRESHOLD*xs, 2*INLIER_THRESHOLD*ys), 0.);

    return ;
}		/* -----  end of method Vision::searchRegion  ----- */

int Vision::_id = 1;