-
Notifications
You must be signed in to change notification settings - Fork 2.7k
/
Copy pathImuTypes.cc
421 lines (355 loc) · 11.2 KB
/
ImuTypes.cc
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
376
377
378
379
380
381
382
383
384
385
386
387
388
389
390
391
392
393
394
395
396
397
398
399
400
401
402
403
404
405
406
407
408
409
410
411
412
413
414
415
416
417
418
419
420
421
/**
* This file is part of ORB-SLAM3
*
* Copyright (C) 2017-2021 Carlos Campos, Richard Elvira, Juan J. Gómez Rodríguez, José M.M. Montiel and Juan D. Tardós, University of Zaragoza.
* Copyright (C) 2014-2016 Raúl Mur-Artal, José M.M. Montiel and Juan D. Tardós, University of Zaragoza.
*
* ORB-SLAM3 is free software: you can redistribute it and/or modify it under the terms of the GNU General Public
* License as published by the Free Software Foundation, either version 3 of the License, or
* (at your option) any later version.
*
* ORB-SLAM3 is distributed in the hope that it will be useful, but WITHOUT ANY WARRANTY; without even
* the implied warranty of MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
* GNU General Public License for more details.
*
* You should have received a copy of the GNU General Public License along with ORB-SLAM3.
* If not, see <http://www.gnu.org/licenses/>.
*/
#include "ImuTypes.h"
#include "Converter.h"
#include "GeometricTools.h"
#include<iostream>
namespace ORB_SLAM3
{
namespace IMU
{
const float eps = 1e-4;
Eigen::Matrix3f NormalizeRotation(const Eigen::Matrix3f &R){
Eigen::JacobiSVD<Eigen::Matrix3f> svd(R, Eigen::ComputeFullU | Eigen::ComputeFullV);
return svd.matrixU() * svd.matrixV().transpose();
}
Eigen::Matrix3f RightJacobianSO3(const float &x, const float &y, const float &z)
{
Eigen::Matrix3f I;
I.setIdentity();
const float d2 = x*x+y*y+z*z;
const float d = sqrt(d2);
Eigen::Vector3f v;
v << x, y, z;
Eigen::Matrix3f W = Sophus::SO3f::hat(v);
if(d<eps) {
return I;
}
else {
return I - W*(1.0f-cos(d))/d2 + W*W*(d-sin(d))/(d2*d);
}
}
Eigen::Matrix3f RightJacobianSO3(const Eigen::Vector3f &v)
{
return RightJacobianSO3(v(0),v(1),v(2));
}
Eigen::Matrix3f InverseRightJacobianSO3(const float &x, const float &y, const float &z)
{
Eigen::Matrix3f I;
I.setIdentity();
const float d2 = x*x+y*y+z*z;
const float d = sqrt(d2);
Eigen::Vector3f v;
v << x, y, z;
Eigen::Matrix3f W = Sophus::SO3f::hat(v);
if(d<eps) {
return I;
}
else {
return I + W/2 + W*W*(1.0f/d2 - (1.0f+cos(d))/(2.0f*d*sin(d)));
}
}
Eigen::Matrix3f InverseRightJacobianSO3(const Eigen::Vector3f &v)
{
return InverseRightJacobianSO3(v(0),v(1),v(2));
}
IntegratedRotation::IntegratedRotation(const Eigen::Vector3f &angVel, const Bias &imuBias, const float &time) {
const float x = (angVel(0)-imuBias.bwx)*time;
const float y = (angVel(1)-imuBias.bwy)*time;
const float z = (angVel(2)-imuBias.bwz)*time;
const float d2 = x*x+y*y+z*z;
const float d = sqrt(d2);
Eigen::Vector3f v;
v << x, y, z;
Eigen::Matrix3f W = Sophus::SO3f::hat(v);
if(d<eps)
{
deltaR = Eigen::Matrix3f::Identity() + W;
rightJ = Eigen::Matrix3f::Identity();
}
else
{
deltaR = Eigen::Matrix3f::Identity() + W*sin(d)/d + W*W*(1.0f-cos(d))/d2;
rightJ = Eigen::Matrix3f::Identity() - W*(1.0f-cos(d))/d2 + W*W*(d-sin(d))/(d2*d);
}
}
Preintegrated::Preintegrated(const Bias &b_, const Calib &calib)
{
Nga = calib.Cov;
NgaWalk = calib.CovWalk;
Initialize(b_);
}
// Copy constructor
Preintegrated::Preintegrated(Preintegrated* pImuPre): dT(pImuPre->dT),C(pImuPre->C), Info(pImuPre->Info),
Nga(pImuPre->Nga), NgaWalk(pImuPre->NgaWalk), b(pImuPre->b), dR(pImuPre->dR), dV(pImuPre->dV),
dP(pImuPre->dP), JRg(pImuPre->JRg), JVg(pImuPre->JVg), JVa(pImuPre->JVa), JPg(pImuPre->JPg), JPa(pImuPre->JPa),
avgA(pImuPre->avgA), avgW(pImuPre->avgW), bu(pImuPre->bu), db(pImuPre->db), mvMeasurements(pImuPre->mvMeasurements)
{
}
void Preintegrated::CopyFrom(Preintegrated* pImuPre)
{
dT = pImuPre->dT;
C = pImuPre->C;
Info = pImuPre->Info;
Nga = pImuPre->Nga;
NgaWalk = pImuPre->NgaWalk;
b.CopyFrom(pImuPre->b);
dR = pImuPre->dR;
dV = pImuPre->dV;
dP = pImuPre->dP;
JRg = pImuPre->JRg;
JVg = pImuPre->JVg;
JVa = pImuPre->JVa;
JPg = pImuPre->JPg;
JPa = pImuPre->JPa;
avgA = pImuPre->avgA;
avgW = pImuPre->avgW;
bu.CopyFrom(pImuPre->bu);
db = pImuPre->db;
mvMeasurements = pImuPre->mvMeasurements;
}
void Preintegrated::Initialize(const Bias &b_)
{
dR.setIdentity();
dV.setZero();
dP.setZero();
JRg.setZero();
JVg.setZero();
JVa.setZero();
JPg.setZero();
JPa.setZero();
C.setZero();
Info.setZero();
db.setZero();
b=b_;
bu=b_;
avgA.setZero();
avgW.setZero();
dT=0.0f;
mvMeasurements.clear();
}
void Preintegrated::Reintegrate()
{
std::unique_lock<std::mutex> lock(mMutex);
const std::vector<integrable> aux = mvMeasurements;
Initialize(bu);
for(size_t i=0;i<aux.size();i++)
IntegrateNewMeasurement(aux[i].a,aux[i].w,aux[i].t);
}
void Preintegrated::IntegrateNewMeasurement(const Eigen::Vector3f &acceleration, const Eigen::Vector3f &angVel, const float &dt)
{
mvMeasurements.push_back(integrable(acceleration,angVel,dt));
// Position is updated firstly, as it depends on previously computed velocity and rotation.
// Velocity is updated secondly, as it depends on previously computed rotation.
// Rotation is the last to be updated.
//Matrices to compute covariance
Eigen::Matrix<float,9,9> A;
A.setIdentity();
Eigen::Matrix<float,9,6> B;
B.setZero();
Eigen::Vector3f acc, accW;
acc << acceleration(0)-b.bax, acceleration(1)-b.bay, acceleration(2)-b.baz;
accW << angVel(0)-b.bwx, angVel(1)-b.bwy, angVel(2)-b.bwz;
avgA = (dT*avgA + dR*acc*dt)/(dT+dt);
avgW = (dT*avgW + accW*dt)/(dT+dt);
// Update delta position dP and velocity dV (rely on no-updated delta rotation)
dP = dP + dV*dt + 0.5f*dR*acc*dt*dt;
dV = dV + dR*acc*dt;
// Compute velocity and position parts of matrices A and B (rely on non-updated delta rotation)
Eigen::Matrix<float,3,3> Wacc = Sophus::SO3f::hat(acc);
A.block<3,3>(3,0) = -dR*dt*Wacc;
A.block<3,3>(6,0) = -0.5f*dR*dt*dt*Wacc;
A.block<3,3>(6,3) = Eigen::DiagonalMatrix<float,3>(dt, dt, dt);
B.block<3,3>(3,3) = dR*dt;
B.block<3,3>(6,3) = 0.5f*dR*dt*dt;
// Update position and velocity jacobians wrt bias correction
JPa = JPa + JVa*dt -0.5f*dR*dt*dt;
JPg = JPg + JVg*dt -0.5f*dR*dt*dt*Wacc*JRg;
JVa = JVa - dR*dt;
JVg = JVg - dR*dt*Wacc*JRg;
// Update delta rotation
IntegratedRotation dRi(angVel,b,dt);
dR = NormalizeRotation(dR*dRi.deltaR);
// Compute rotation parts of matrices A and B
A.block<3,3>(0,0) = dRi.deltaR.transpose();
B.block<3,3>(0,0) = dRi.rightJ*dt;
// Update covariance
C.block<9,9>(0,0) = A * C.block<9,9>(0,0) * A.transpose() + B*Nga*B.transpose();
C.block<6,6>(9,9) += NgaWalk;
// Update rotation jacobian wrt bias correction
JRg = dRi.deltaR.transpose()*JRg - dRi.rightJ*dt;
// Total integrated time
dT += dt;
}
void Preintegrated::MergePrevious(Preintegrated* pPrev)
{
if (pPrev==this)
return;
std::unique_lock<std::mutex> lock1(mMutex);
std::unique_lock<std::mutex> lock2(pPrev->mMutex);
Bias bav;
bav.bwx = bu.bwx;
bav.bwy = bu.bwy;
bav.bwz = bu.bwz;
bav.bax = bu.bax;
bav.bay = bu.bay;
bav.baz = bu.baz;
const std::vector<integrable > aux1 = pPrev->mvMeasurements;
const std::vector<integrable> aux2 = mvMeasurements;
Initialize(bav);
for(size_t i=0;i<aux1.size();i++)
IntegrateNewMeasurement(aux1[i].a,aux1[i].w,aux1[i].t);
for(size_t i=0;i<aux2.size();i++)
IntegrateNewMeasurement(aux2[i].a,aux2[i].w,aux2[i].t);
}
void Preintegrated::SetNewBias(const Bias &bu_)
{
std::unique_lock<std::mutex> lock(mMutex);
bu = bu_;
db(0) = bu_.bwx-b.bwx;
db(1) = bu_.bwy-b.bwy;
db(2) = bu_.bwz-b.bwz;
db(3) = bu_.bax-b.bax;
db(4) = bu_.bay-b.bay;
db(5) = bu_.baz-b.baz;
}
IMU::Bias Preintegrated::GetDeltaBias(const Bias &b_)
{
std::unique_lock<std::mutex> lock(mMutex);
return IMU::Bias(b_.bax-b.bax,b_.bay-b.bay,b_.baz-b.baz,b_.bwx-b.bwx,b_.bwy-b.bwy,b_.bwz-b.bwz);
}
Eigen::Matrix3f Preintegrated::GetDeltaRotation(const Bias &b_)
{
std::unique_lock<std::mutex> lock(mMutex);
Eigen::Vector3f dbg;
dbg << b_.bwx-b.bwx,b_.bwy-b.bwy,b_.bwz-b.bwz;
return NormalizeRotation(dR * Sophus::SO3f::exp(JRg * dbg).matrix());
}
Eigen::Vector3f Preintegrated::GetDeltaVelocity(const Bias &b_)
{
std::unique_lock<std::mutex> lock(mMutex);
Eigen::Vector3f dbg, dba;
dbg << b_.bwx-b.bwx,b_.bwy-b.bwy,b_.bwz-b.bwz;
dba << b_.bax-b.bax,b_.bay-b.bay,b_.baz-b.baz;
return dV + JVg * dbg + JVa * dba;
}
Eigen::Vector3f Preintegrated::GetDeltaPosition(const Bias &b_)
{
std::unique_lock<std::mutex> lock(mMutex);
Eigen::Vector3f dbg, dba;
dbg << b_.bwx-b.bwx,b_.bwy-b.bwy,b_.bwz-b.bwz;
dba << b_.bax-b.bax,b_.bay-b.bay,b_.baz-b.baz;
return dP + JPg * dbg + JPa * dba;
}
Eigen::Matrix3f Preintegrated::GetUpdatedDeltaRotation()
{
std::unique_lock<std::mutex> lock(mMutex);
return NormalizeRotation(dR * Sophus::SO3f::exp(JRg*db.head(3)).matrix());
}
Eigen::Vector3f Preintegrated::GetUpdatedDeltaVelocity()
{
std::unique_lock<std::mutex> lock(mMutex);
return dV + JVg * db.head(3) + JVa * db.tail(3);
}
Eigen::Vector3f Preintegrated::GetUpdatedDeltaPosition()
{
std::unique_lock<std::mutex> lock(mMutex);
return dP + JPg*db.head(3) + JPa*db.tail(3);
}
Eigen::Matrix3f Preintegrated::GetOriginalDeltaRotation() {
std::unique_lock<std::mutex> lock(mMutex);
return dR;
}
Eigen::Vector3f Preintegrated::GetOriginalDeltaVelocity() {
std::unique_lock<std::mutex> lock(mMutex);
return dV;
}
Eigen::Vector3f Preintegrated::GetOriginalDeltaPosition()
{
std::unique_lock<std::mutex> lock(mMutex);
return dP;
}
Bias Preintegrated::GetOriginalBias()
{
std::unique_lock<std::mutex> lock(mMutex);
return b;
}
Bias Preintegrated::GetUpdatedBias()
{
std::unique_lock<std::mutex> lock(mMutex);
return bu;
}
Eigen::Matrix<float,6,1> Preintegrated::GetDeltaBias()
{
std::unique_lock<std::mutex> lock(mMutex);
return db;
}
void Bias::CopyFrom(Bias &b)
{
bax = b.bax;
bay = b.bay;
baz = b.baz;
bwx = b.bwx;
bwy = b.bwy;
bwz = b.bwz;
}
std::ostream& operator<< (std::ostream &out, const Bias &b)
{
if(b.bwx>0)
out << " ";
out << b.bwx << ",";
if(b.bwy>0)
out << " ";
out << b.bwy << ",";
if(b.bwz>0)
out << " ";
out << b.bwz << ",";
if(b.bax>0)
out << " ";
out << b.bax << ",";
if(b.bay>0)
out << " ";
out << b.bay << ",";
if(b.baz>0)
out << " ";
out << b.baz;
return out;
}
void Calib::Set(const Sophus::SE3<float> &sophTbc, const float &ng, const float &na, const float &ngw, const float &naw) {
mbIsSet = true;
const float ng2 = ng*ng;
const float na2 = na*na;
const float ngw2 = ngw*ngw;
const float naw2 = naw*naw;
// Sophus/Eigen
mTbc = sophTbc;
mTcb = mTbc.inverse();
Cov.diagonal() << ng2, ng2, ng2, na2, na2, na2;
CovWalk.diagonal() << ngw2, ngw2, ngw2, naw2, naw2, naw2;
}
Calib::Calib(const Calib &calib)
{
mbIsSet = calib.mbIsSet;
// Sophus/Eigen parameters
mTbc = calib.mTbc;
mTcb = calib.mTcb;
Cov = calib.Cov;
CovWalk = calib.CovWalk;
}
} //namespace IMU
} //namespace ORB_SLAM2