forked from raulmur/ORB_SLAM2
-
Notifications
You must be signed in to change notification settings - Fork 0
/
autorally.yaml
116 lines (99 loc) · 3.37 KB
/
autorally.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
%YAML:1.0
#--------------------------------------------------------------------------------------------
# Camera Parameters. Adjust them!
#--------------------------------------------------------------------------------------------
# Camera calibration and distortion parameters (OpenCV)
Camera.fx: 837.639837
Camera.fy: 840.813137
Camera.cx: 620.044329
Camera.cy: 509.841225
Camera.k1: 0.0
Camera.k2: 0.0
Camera.p1: 0.0
Camera.p2: 0.0
Camera.width: 1280
Camera.height: 1024
# Camera frames per second
Camera.fps: 40.0
# stereo baseline times fx 47.90639384423901
Camera.bf: 200.0
# Color order of the images (0: BGR, 1: RGB. It is ignored if images are grayscale)
Camera.RGB: 1
# Close/Far threshold. Baseline times.
ThDepth: 35
#--------------------------------------------------------------------------------------------
# Stereo Rectification. Only if you need to pre-rectify the images.
# Camera.fx, .fy, etc must be the same as in LEFT.P
#--------------------------------------------------------------------------------------------
LEFT.height: 1280
LEFT.width: 1024
LEFT.D: !!opencv-matrix
rows: 1
cols: 5
dt: d
data:[-0.221363, 0.078426, -0.000684, 0.000983, 0.000000]
LEFT.K: !!opencv-matrix
rows: 3
cols: 3
dt: d
data: [837.639837, 0, 620.044329, 0, 840.813137, 509.841225, 0, 0, 1]
LEFT.R: !!opencv-matrix
rows: 3
cols: 3
dt: d
data: [0.999561, -0.000419, -0.029615, 0.000418, 1, -0.000051, 0.029615, 0.000039, 0.999561]
LEFT.P: !!opencv-matrix
rows: 3
cols: 4
dt: d
data: [788.519761, 0, 659.850090, 0, 0, 788.519761, 513.742554, 0, 0, 0, 1, 0]
RIGHT.height: 1280
RIGHT.width: 1024
RIGHT.D: !!opencv-matrix
rows: 1
cols: 5
dt: d
data:[-0.224415, 0.085518, -0.000845, 0.000148, 0]
RIGHT.K: !!opencv-matrix
rows: 3
cols: 3
dt: d
data: [843.099384, 0, 637.057540, 0, 845.451384, 521.100518, 0, 0, 1]
RIGHT.R: !!opencv-matrix
rows: 3
cols: 3
dt: d
data: [0.999805, 0.003565, -0.019400, -0.003564, 0.999994, 0.000079, 0.019400, -0.000010, 0.999812]
RIGHT.P: !!opencv-matrix
rows: 3
cols: 4
dt: d
data: [788.519761, 0, 659.850090, -115.759101, 0, 788.519761, 513.742554, 0, 0, 0, 1, 0]
#--------------------------------------------------------------------------------------------
# ORB Parameters
#--------------------------------------------------------------------------------------------
# ORB Extractor: Number of features per image
ORBextractor.nFeatures: 1200
# ORB Extractor: Scale factor between levels in the scale pyramid
ORBextractor.scaleFactor: 1.2
# ORB Extractor: Number of levels in the scale pyramid
ORBextractor.nLevels: 8
# ORB Extractor: Fast threshold
# Image is divided in a grid. At each cell FAST are extracted imposing a minimum response.
# Firstly we impose iniThFAST. If no corners are detected we impose a lower value minThFAST
# You can lower these values if your images have low contrast
ORBextractor.iniThFAST: 20
ORBextractor.minThFAST: 7
#--------------------------------------------------------------------------------------------
# Viewer Parameters
#--------------------------------------------------------------------------------------------
Viewer.KeyFrameSize: 0.05
Viewer.KeyFrameLineWidth: 1
Viewer.GraphLineWidth: 0.9
Viewer.PointSize:2
Viewer.CameraSize: 0.08
Viewer.CameraLineWidth: 3
Viewer.ViewpointX: 0
Viewer.ViewpointY: -0.7
Viewer.ViewpointZ: -1.8
Viewer.ViewpointF: 500