-
Notifications
You must be signed in to change notification settings - Fork 14
/
costfunctions.h
375 lines (350 loc) · 9.65 KB
/
costfunctions.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
351
352
353
354
355
356
357
358
359
360
361
362
363
364
365
366
367
368
369
370
371
372
373
374
375
#pragma once
struct costVertical {
costVertical() {}
template <typename T>
bool operator()(const T* x, T* residual) const {
T vert[3] = {0, 1, 0}, vert2[3];
ceres::AngleAxisRotatePoint(x, vert, vert2);
residual[0] = -1
+ vert[0]*vert2[0]
+ vert[1]*vert2[1]
+ vert[2]*vert2[2];
}
};
struct cost3DPD {
// 3DPD
cost3DPD(
double point_x,
double point_y,
double point_z,
double normal_x,
double normal_y,
double normal_z,
double offset_x,
double offset_y,
double offset_z) :
point_x(point_x),
point_y(point_y),
point_z(point_z),
normal_x(normal_x),
normal_y(normal_y),
normal_z(normal_z),
offset_x(offset_x),
offset_y(offset_y),
offset_z(offset_z) {}
template <typename T>
bool operator()(const T* x, T* residual) const {
// x[0], x[1], x[2] are angle-axis rotation
T M[3], M_original[3];
M_original[0] = T(point_x);
M_original[1] = T(point_y);
M_original[2] = T(point_z);
ceres::AngleAxisRotatePoint(x, M_original, M);
M[0] += x[3] - T(offset_x);
M[1] += x[4] - T(offset_y);
M[2] += x[5] - T(offset_z);
residual[0] = M[0] * T(normal_x)
+ M[1] * T(normal_y)
+ M[2] * T(normal_z);
return true;
}
double point_x, point_y, point_z,
normal_x, normal_y, normal_z,
offset_x, offset_y, offset_z;
};
struct cost3D3D {
// 3D point to 3D point distance
cost3D3D(
double m_x,
double m_y,
double m_z,
double s_x,
double s_y,
double s_z) :
m_x(m_x),
m_y(m_y),
m_z(m_z),
s_x(s_x),
s_y(s_y),
s_z(s_z) {}
template <typename T>
bool operator()(const T* x, T* residual) const {
T M[3], M_original[3];
M_original[0] = T(m_x);
M_original[1] = T(m_y);
M_original[2] = T(m_z);
ceres::AngleAxisRotatePoint(x, M_original, M);
residual[0] = M[0] + x[3] - T(s_x);
residual[1] = M[1] + x[4] - T(s_y);
residual[2] = M[2] + x[5] - T(s_z);
return true;
}
double m_x, m_y, m_z,
s_x, s_y, s_z;
};
struct cost3D2D {
// 3D point to 2D point reprojection distance
cost3D2D(
double m_x,
double m_y,
double m_z,
double s_x,
double s_y,
double t_x,
double t_y,
double t_z) :
m_x(m_x),
m_y(m_y),
m_z(m_z),
s_x(s_x),
s_y(s_y),
t_x(t_x),
t_y(t_y),
t_z(t_z) {}
template <typename T>
bool operator()(const T* x, T* residual) const {
T M[3], M_original[3];
M_original[0] = T(m_x);
M_original[1] = T(m_y);
M_original[2] = T(m_z);
ceres::AngleAxisRotatePoint(x, M_original, M);
M[0] += x[3] + T(t_x);
M[1] += x[4] + T(t_y);
M[2] += x[5] + T(t_z);
residual[0] = M[0] - T(s_x) * M[2];
residual[1] = M[1] - T(s_y) * M[2];
return true;
}
double m_x, m_y, m_z,
s_x, s_y,
t_x, t_y, t_z;
};
struct cost2D3D {
// 2D point to 3D point reprojection distance
cost2D3D(
double m_x,
double m_y,
double m_z,
double s_x,
double s_y,
double t_x,
double t_y,
double t_z) :
m_x(m_x),
m_y(m_y),
m_z(m_z),
s_x(s_x),
s_y(s_y),
t_x(t_x),
t_y(t_y),
t_z(t_z) {}
template <typename T>
bool operator()(const T* x, T* residual) const {
T M[3], M_original[3], rot[3];
rot[0] = -x[0];
rot[1] = -x[1];
rot[2] = -x[2];
M_original[0] = T(m_x) - x[3];
M_original[1] = T(m_y) - x[4];
M_original[2] = T(m_z) - x[5];
ceres::AngleAxisRotatePoint(rot, M_original, M);
M[0] += T(t_x);
M[1] += T(t_y);
M[2] += T(t_z);
residual[0] = M[0] - T(s_x) * M[2];
residual[1] = M[1] - T(s_y) * M[2];
return true;
}
double m_x, m_y, m_z,
s_x, s_y,
t_x, t_y, t_z;
};
struct cost2D2D {
// 2D point to 2D point epipolar constraint
cost2D2D(
double m_x,
double m_y,
double s_x,
double s_y,
double t_x,
double t_y,
double t_z) :
m_x(m_x),
m_y(m_y),
s_x(s_x),
s_y(s_y),
t_x(t_x),
t_y(t_y),
t_z(t_z) {}
template <typename T>
bool operator()(const T* x, T* residual) const {
T M[3], M_original[3];
M_original[0] = T(m_x);
M_original[1] = T(m_y);
M_original[2] = T(1.0);
ceres::AngleAxisRotatePoint(x, M_original, M);
// E = [t]_x R
// S^T E M = residual
// S dot (t cross (R M)) = residual
T Rtt[3] = {T(t_x), T(t_y), T(t_z)}, tt[3];
ceres::AngleAxisRotatePoint(x, Rtt, tt);
T tt_x = -tt[0] + x[3] + T(t_x),
tt_y = -tt[1] + x[4] + T(t_y),
tt_z = -tt[2] + x[5] + T(t_z);
T tn = sqrt(tt_x*tt_x + tt_y*tt_y + tt_z*tt_z);
tt_x /= tn;
tt_y /= tn;
tt_z /= tn;
residual[0] =
M[0] * (-s_y * tt_z + tt_y) +
M[1] * ( s_x * tt_z - tt_x) +
M[2] * (-s_x * tt_y + s_y * tt_x);
return true;
}
double m_x, m_y,
s_x, s_y,
t_x, t_y, t_z;
};
struct bundle2D {
bundle2D(
double s_x,
double s_y,
double t_x,
double t_y,
double t_z) :
s_x(s_x),
s_y(s_y),
t_x(t_x),
t_y(t_y),
t_z(t_z) {}
template <typename T>
bool operator()(const T* point, const T* camera, T* residual) const {
T M[3], M_original[3], rot[3];
rot[0] = -camera[0];
rot[1] = -camera[1];
rot[2] = -camera[2];
M_original[0] = T(point[0]) - camera[3];
M_original[1] = T(point[1]) - camera[4];
M_original[2] = T(point[2]) - camera[5];
ceres::AngleAxisRotatePoint(rot, M_original, M);
M[0] += T(t_x);
M[1] += T(t_y);
M[2] += T(t_z);
residual[0] = M[0] - s_x * M[2];
residual[1] = M[1] - s_y * M[2];
return true;
}
double s_x, s_y,
t_x, t_y, t_z;
};
struct bundle3D {
bundle3D(
double s_x,
double s_y,
double s_z,
double weight) :
s_x(s_x),
s_y(s_y),
s_z(s_z),
weight(weight) {}
template <typename T>
bool operator()(const T* point, const T* camera, T* residual) const {
T M[3], M_original[3], rot[3];
rot[0] = -camera[0];
rot[1] = -camera[1];
rot[2] = -camera[2];
M_original[0] = T(point[0]) - camera[3];
M_original[1] = T(point[1]) - camera[4];
M_original[2] = T(point[2]) - camera[5];
ceres::AngleAxisRotatePoint(rot, M_original, M);
residual[0] = weight * (M[0] - s_x);
residual[1] = weight * (M[1] - s_y);
residual[2] = weight * (M[2] - s_z);
return true;
}
double s_x, s_y, s_z,
weight;
};
struct triangulation2D {
triangulation2D(
double s_x,
double s_y,
double cam_0,
double cam_1,
double cam_2,
double cam_3,
double cam_4,
double cam_5,
double t_x,
double t_y,
double t_z) :
s_x(s_x),
s_y(s_y),
cam_0(cam_0),
cam_1(cam_1),
cam_2(cam_2),
cam_3(cam_3),
cam_4(cam_4),
cam_5(cam_5),
t_x(t_x),
t_y(t_y),
t_z(t_z) {}
template <typename T>
bool operator()(const T* point, T* residual) const {
T M[3], M_original[3], rot[3];
rot[0] = -T(cam_0);
rot[1] = -T(cam_1);
rot[2] = -T(cam_2);
M_original[0] = T(point[0]) - T(cam_3);
M_original[1] = T(point[1]) - T(cam_4);
M_original[2] = T(point[2]) - T(cam_5);
ceres::AngleAxisRotatePoint(rot, M_original, M);
M[0] += T(t_x);
M[1] += T(t_y);
M[2] += T(t_z);
residual[0] = M[0] - T(s_x) * M[2];
residual[1] = M[1] - T(s_y) * M[2];
return true;
}
double s_x, s_y,
cam_0, cam_1, cam_2, cam_3, cam_4, cam_5,
t_x, t_y, t_z;
};
struct triangulation3D {
triangulation3D(
double s_x,
double s_y,
double s_z,
double cam_0,
double cam_1,
double cam_2,
double cam_3,
double cam_4,
double cam_5) :
s_x(s_x),
s_y(s_y),
s_z(s_z),
cam_0(cam_0),
cam_1(cam_1),
cam_2(cam_2),
cam_3(cam_3),
cam_4(cam_4),
cam_5(cam_5) {}
template <typename T>
bool operator()(const T* point, T* residual) const {
T M[3], M_original[3], rot[3];
rot[0] = -T(cam_0);
rot[1] = -T(cam_1);
rot[2] = -T(cam_2);
M_original[0] = T(point[0]) - T(cam_3);
M_original[1] = T(point[1]) - T(cam_4);
M_original[2] = T(point[2]) - T(cam_5);
ceres::AngleAxisRotatePoint(rot, M_original, M);
residual[0] = M[0] - T(s_x);
residual[1] = M[1] - T(s_y);
residual[2] = M[2] - T(s_z);
return true;
}
double s_x, s_y, s_z,
cam_0, cam_1, cam_2, cam_3, cam_4, cam_5;
};