forked from DapengFeng/S3E
-
Notifications
You must be signed in to change notification settings - Fork 0
/
bob.yaml
125 lines (114 loc) · 4.23 KB
/
bob.yaml
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
%YAML:1.0
#--------------------------------------------------------------------------------------------
# Left Camera Parameters.
#--------------------------------------------------------------------------------------------
Camera.type: "PinHole"
# Camera calibration and distortion parameters (OpenCV) (equal for both cameras after stereo rectification)
Camera.fx: 1176.371989001733
Camera.fy: 1176.092984580754
Camera.cx: 621.676298301324
Camera.cy: 508.182115727477
Camera.k1: -0.052418753922603
Camera.k2: 0.104682361259496
Camera.p1: 0.000650517607061
Camera.p2: 0.000103793518711
Camera.width: 1224
Camera.height: 1024
# Camera frames per second
Camera.fps: 10.0
# stereo baseline times fx (unit: m x pixel)
Camera.bf: 423.4939160406239
#--------------------------------------------------------------------------------------------
# IMU noise
#--------------------------------------------------------------------------------------------
IMU.NoiseGyro: 1.0084886221461694e-02
IMU.NoiseAcc: 1.0557715622632996e-02
IMU.GyroWalk: 9.8778648600726277e-05
IMU.AccWalk: 2.3084619195565281e-04
IMU.Frequency: 100
# Transformation from left camera to imu
Tic: !!opencv-matrix
rows: 4
cols: 4
dt: d
data: [0.0004156, -0.01277515, 0.99991831, 0.15076999,
-0.99999158, -0.00408635, 0.00036342, 0.1531545,
0.00408138, -0.99991004, -0.01277674, 0.01004714,
0.0, 0.0, 0.0, 1.0]
#--------------------------------------------------------------------------------------------
# Stereo Rectification. Only if you need to pre-rectify the images.
#--------------------------------------------------------------------------------------------
LEFT.height: 1024
LEFT.width: 1224
LEFT.D: !!opencv-matrix
rows: 1
cols: 5
dt: d
data: [-0.052418753922603, 0.104682361259496, 0.000650517607061, 0.000103793518711, 0.0]
LEFT.K: !!opencv-matrix
rows: 3
cols: 3
dt: d
data: [1176.371989001733, 0.0, 621.676298301324,
0.0, 1176.092984580754, 508.182115727477,
0.0, 0.0, 1.0]
LEFT.R: !!opencv-matrix
rows: 3
cols: 3
dt: d
data: [1.0, 0.0, 0.0,
0.0, 1.0, 0.0,
0.0, 0.0, 1.0]
LEFT.Rf: !!opencv-matrix
rows: 3
cols: 3
dt: d
data: [1.0, 0.0, 0.0,
0.0, 1.0, 0.0,
0.0, 0.0, 1.0]
LEFT.P: !!opencv-matrix
rows: 3
cols: 4
dt: d
data: [1176.371989001733, 0.0, 621.676298301324, 0.0,
0.0, 1176.092984580754, 508.182115727477, 0.0,
0.0, 0.0, 1.0, 0.0]
RIGHT.height: 1024
RIGHT.width: 1224
RIGHT.D: !!opencv-matrix
rows: 1
cols: 5
dt: d
data: [-0.053314338222019, 0.099513356190201, -0.000114531609168, 0.001057111311330, 0.0]
RIGHT.K: !!opencv-matrix
rows: 3
cols: 3
dt: d
data: [1170.903035724522, 0.0, 602.239017335193,
0.0, 1170.731039292330, 505.701781863552,
0.0, 0.0, 1.0]
RIGHT.R: !!opencv-matrix
rows: 3
cols: 3
dt: d
data: [0.999988904147781, 0.002977057860333, -0.003650850286635,
-0.002963513067231, 0.999988727228776, 0.003709852513600,
0.003661853577021, -0.003698992007094, 0.999986454051510]
RIGHT.P: !!opencv-matrix
rows: 3
cols: 4
dt: d
data: [1170.903035724522, 0.0, 602.239017335193, -364.7958668586873,
0.0, 1170.731039292330, 505.701781863552, 1.3954592304343,
0.0, 0.0, 1.0, -12.6923711243586]
#--------------------------------------------------------------------------------------------
# Transformation from left camera to lidar
#--------------------------------------------------------------------------------------------
Tlc: !!opencv-matrix
rows: 4
cols: 4
dt: d
data: [0.017870010543876, -0.017600720528060, 0.999685389190047, 0.132943148638482,
-0.999728769020931, -0.015249506692405, 0.017602299211548, 0.201060820335298,
0.014934895883679, -0.999728796815682, -0.017868455512781, -0.083131958281528,
0.0, 0.0, 0.0, 1.000000000000000]