-
Notifications
You must be signed in to change notification settings - Fork 1
/
visualodom.h
350 lines (282 loc) · 10.6 KB
/
visualodom.h
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
313
314
315
316
317
318
319
320
321
322
323
324
325
326
327
328
329
330
331
332
333
334
335
336
337
338
339
340
341
342
343
344
345
346
347
348
349
350
#ifndef VISUALODOM_H
#define VISUALODOM_H
#include <iostream>
#include "stereocam.h"
#include <opencv2/opencv.hpp>
#include "opencv2/core/core.hpp"
#include "opencv2/features2d/features2d.hpp"
#include "opencv2/nonfree/features2d.hpp"
#include "opencv2/highgui/highgui.hpp"
#include "opencv2/nonfree/nonfree.hpp"
#include <eigen3/Eigen/Dense>
#include "opencv2/imgproc/imgproc.hpp"
using namespace std;
using namespace cv;
#define MIN_MOTION 1.5
class VisualOdom
{
public:
// Variables
vector<KeyPoint> keypoints_Prev, keypoints_Curr;
Mat descriptors_Prev, descriptors_Curr;
Mat Points3D; Mat Translation; Mat Rotation;
StereoCam StereoRig, StereoRig_Prev;
Mat Synthetic_Image;
// 3d Point cloud
Mat Pts_3D; // 3D point coordinates
Mat Pts_Des; // Corresponding Descriptors
Mat Pose;
Mat CarDim;
Mat Pose_local;
bool flag_add_points=true;
// Stereo rigs
VisualOdom();
void OpenDim(string ParametersFile); // Open location of the camera on the car
bool MotionEst(double size, double level, double min_disp, double y_thresh, double bi_radius, bool display);
void ClearPointCloud(Mat PoseRear, double treshdist); // Remove teh points behind the rear car
void ImageSynthesis(Mat PoseRear, Size RearImSize, Mat IntrinsicParam);
Mat ROI_Estimation(Mat IntrinsicRear, Mat PoseRear, Size RearimgSize, Mat ImageDis, bool display); // Estimate the ROI using the car dimensions
void MotionEstMatching (double thresh, bool display);
};
// FOR CERES
struct LeftReprojectionError {
LeftReprojectionError(double u, double v, double x, double y, double z, double f, double cx, double cy)
: u(u), v(v), x(x), y(y), z(z), f(f), cx(cx), cy(cy) {}
template <typename T>
bool operator()(const T* const camera,
T* residuals) const {
// camera[0,1,2] are the angle-axis rotation.
T point[3];
point[0] = T(x);
point[1] = T(y);
point[2] = T(z);
T p[3];
ceres::AngleAxisRotatePoint(camera, point, p);
// camera[3,4,5] are the translation.
p[0] += camera[3];
p[1] += camera[4];
p[2] += camera[5];
p[0] /= p[2];
p[1] /= p[2];
T up = T(f)*p[0] + T(cx);
T vp = T(f)*p[1] + T(cy);
// The error is the difference between the predicted and observed position.
residuals[0] = up - T(u);
residuals[1] = vp - T(v);
return true;
}
// Factory to hide the construction of the CostFunction object from
// the client code.
static ceres::CostFunction* Create(const double u,
const double v,
const double x,
const double y,
const double z,
const double f,
const double cx,
const double cy) {
return (new ceres::AutoDiffCostFunction<LeftReprojectionError, 2, 6>(new LeftReprojectionError(u, v, x, y, z, f, cx, cy)));
}
double u, v;
double x, y, z;
double f;
double cx;
double cy;
};
struct RightReprojectionError {
RightReprojectionError(double u, double v, double x, double y, double z, double f, double cx, double cy, double baseline)
: u(u), v(v), x(x), y(y), z(z), f(f), cx(cx), cy(cy), baseline(baseline) {}
template <typename T>
bool operator()(const T* const camera,
T* residuals) const {
// camera[0,1,2] are the angle-axis rotation.
T point[3];
point[0] = T(x);
point[1] = T(y);
point[2] = T(z);
T p[3];
ceres::AngleAxisRotatePoint(camera, point, p);
// camera[3,4,5] are the translation.
p[0] += camera[3];
p[1] += camera[4];
p[2] += camera[5];
p[0] -= T(baseline);
p[0] /= p[2];
p[1] /= p[2];
T up = T(f)*p[0] + T(cx);
T vp = T(f)*p[1] + T(cy);
// The error is the difference between the predicted and observed position.
residuals[0] = up - T(u);
residuals[1] = vp - T(v);
return true;
}
// Factory to hide the construction of the CostFunction object from
// the client code.
static ceres::CostFunction* Create(const double u,
const double v,
const double x,
const double y,
const double z,
const double f,
const double cx,
const double cy,
const double baseline) {
return (new ceres::AutoDiffCostFunction<RightReprojectionError, 2, 6>(new RightReprojectionError(u, v, x, y, z, f, cx, cy, baseline)));
}
double u, v;
double x, y, z;
double f;
double cx;
double cy;
double baseline;
};
// Approach 2: optimize points and the pose
struct LeftReprojectionError2 {
LeftReprojectionError2(double u, double v, double f, double cx, double cy)
: u(u), v(v), f(f), cx(cx), cy(cy) {}
template <typename T>
bool operator()(const T* const camera,
const T* const point,
T* residuals) const {
// camera[0,1,2] are the angle-axis rotation.
T p[3];
ceres::AngleAxisRotatePoint(camera, point, p);
// camera[3,4,5] are the translation.
p[0] += camera[3];
p[1] += camera[4];
p[2] += camera[5];
p[0] /= p[2];
p[1] /= p[2];
T up = T(f)*p[0] + T(cx);
T vp = T(f)*p[1] + T(cy);
// The error is the difference between the predicted and observed position.
residuals[0] = up - T(u);
residuals[1] = vp - T(v);
return true;
}
// Factory to hide the construction of the CostFunction object from
// the client code.
static ceres::CostFunction* Create(const double u,
const double v,
const double f,
const double cx,
const double cy) {
return (new ceres::AutoDiffCostFunction<LeftReprojectionError2, 2, 6, 3>(new LeftReprojectionError2(u, v, f, cx, cy)));
}
double u, v;
double f;
double cx;
double cy;
};
struct RightReprojectionError2 {
RightReprojectionError2(double u, double v, double f, double cx, double cy, double baseline)
: u(u), v(v), f(f), cx(cx), cy(cy), baseline(baseline) {}
template <typename T>
bool operator()(const T* const camera,
const T* const point,
T* residuals) const {
// camera[0,1,2] are the angle-axis rotation.
T p[3];
ceres::AngleAxisRotatePoint(camera, point, p);
// camera[3,4,5] are the translation.
p[0] += camera[3];
p[1] += camera[4];
p[2] += camera[5];
p[0] -= T(baseline);
p[0] /= p[2];
p[1] /= p[2];
T up = T(f)*p[0] + T(cx);
T vp = T(f)*p[1] + T(cy);
// The error is the difference between the predicted and observed position.
residuals[0] = up - T(u);
residuals[1] = vp - T(v);
return true;
}
// Factory to hide the construction of the CostFunction object from
// the client code.
static ceres::CostFunction* Create(const double u,
const double v,
const double f,
const double cx,
const double cy,
const double baseline) {
return (new ceres::AutoDiffCostFunction<RightReprojectionError2, 2, 6, 3>(new RightReprojectionError2(u, v, f, cx, cy, baseline)));
}
double u, v;
double f;
double cx;
double cy;
double baseline;
};
struct LeftReprojectionError3 {
LeftReprojectionError3(double u, double v, double f, double cx, double cy)
: u(u), v(v), f(f), cx(cx), cy(cy) {}
template <typename T>
bool operator()(const T* const point,
T* residuals) const {
// camera[0,1,2] are the angle-axis rotation.
T p[3];
p[0] = point[0];
p[1] = point[1];
p[2] = point[2];
p[0] /= p[2];
p[1] /= p[2];
T up = T(f)*p[0] + T(cx);
T vp = T(f)*p[1] + T(cy);
// The error is the difference between the predicted and observed position.
residuals[0] = up - T(u);
residuals[1] = vp - T(v);
return true;
}
// Factory to hide the construction of the CostFunction object from
// the client code.
static ceres::CostFunction* Create(const double u,
const double v,
const double f,
const double cx,
const double cy) {
return (new ceres::AutoDiffCostFunction<LeftReprojectionError3, 2, 3>(new LeftReprojectionError3(u, v, f, cx, cy)));
}
double u, v;
double f;
double cx;
double cy;
};
struct RightReprojectionError3 {
RightReprojectionError3(double u, double v, double f, double cx, double cy, double baseline)
: u(u), v(v), f(f), cx(cx), cy(cy), baseline(baseline) {}
template <typename T>
bool operator()(const T* const point,
T* residuals) const {
// camera[0,1,2] are the angle-axis rotation.
T p[3];
p[0] = point[0];
p[1] = point[1];
p[2] = point[2];
p[0] -= T(baseline);
p[0] /= p[2];
p[1] /= p[2];
T up = T(f)*p[0] + T(cx);
T vp = T(f)*p[1] + T(cy);
// The error is the difference between the predicted and observed position.
residuals[0] = up - T(u);
residuals[1] = vp - T(v);
return true;
}
// Factory to hide the construction of the CostFunction object from
// the client code.
static ceres::CostFunction* Create(const double u,
const double v,
const double f,
const double cx,
const double cy,
const double baseline) {
return (new ceres::AutoDiffCostFunction<RightReprojectionError3, 2, 3>(new RightReprojectionError3(u, v, f, cx, cy, baseline)));
}
double u, v;
double f;
double cx;
double cy;
double baseline;
};
#endif // VISUALODOM_H