-
Notifications
You must be signed in to change notification settings - Fork 0
/
Copy pathruncam_720p.yaml
129 lines (108 loc) · 2.32 KB
/
runcam_720p.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
126
127
128
129
# EuRoC monocular model
Camera:
name: "runcam640"
setup: "monocular"
model: "perspective"
#c310
#fx: 1523.12382
#fy: 1466.29103
#cx: 1002.87873
#cy: 530.10411
#k1: -0.587138
#k2: 0.248748
#p1: -0.002170
#p2: -0.008611
#k3: 0.000000
## runcam 1920 1080
#camera_matrix:
# rows: 3
# cols: 3
# data: [1523.12382, 0. , 1002.87873,
# 0. , 1466.29103, 530.10411,
# 0. , 0. , 1. ]
#distortion_model: plumb_bob
#distortion_coefficients:
# rows: 1
# cols: 5
# data: [-0.587138, 0.248748, -0.002170, -0.008611, 0.000000
# ---runcam 640 480---
# fx: 331.867705
# fy: 716.606937
# cx: 288.803289
# cy: 206.501952
# k1: -0.276736
# k2: 0.051486
# p1: 0.001675
# p2: 1.76187114e-05
# k3: 0.000000
# fps: 30.0
# cols: 1280
# rows: 720
# color_order: "BGRA"
# ---runcam 1280 720 ---
# camera matrix
# 713.394872 0.000000 627.162907
# 0.000000 716.606937 320.816944
# 0.000000 0.000000 1.000000
# distortion
# -0.317813 0.068975 0.001900 0.000117 0.000000
# rectification
# 1.000000 0.000000 0.000000
# 0.000000 1.000000 0.000000
# 0.000000 0.000000 1.000000
# projection
# 464.330353 0.000000 625.814992 0.000000
# 0.000000 648.127808 313.098624 0.000000
# 0.000000 0.000000 1.000000 0.000000
fx: 713.394872
fy: 716.606937
cx: 627.162907
cy: 320.816944
k1: -0.317813
k2: 0.068975
p1: 0.001900
p2: 0.000117
k3: 0.000000
fps: 30.0
cols: 1280
rows: 720
color_order: "BGRA"
Preprocessing:
min_size: 800
Feature:
name: "default ORB feature extraction setting"
scale_factor: 1.2
num_levels: 8
ini_fast_threshold: 20
min_fast_threshold: 7
Mapping:
backend: "g2o"
baseline_dist_thr_ratio: 0.02
redundant_obs_ratio_thr: 0.9
num_covisibilities_for_landmark_generation: 20
num_covisibilities_for_landmark_fusion: 20
Tracking:
backend: "g2o"
LoopDetector:
backend: "g2o"
enabled: true
reject_by_graph_distance: true
min_distance_on_graph: 50
System:
map_format: "msgpack"
PangolinViewer:
keyframe_size: 0.07
keyframe_line_width: 1
graph_line_width: 1
point_size: 2
camera_size: 0.08
camera_line_width: 3
viewpoint_x: 0
viewpoint_y: -0.65
viewpoint_z: -1.9
viewpoint_f: 400
# MarkerModel:
# type: "aruco"
# width: 0.15
# marker_size: 6
# max_markers: 250