-
Notifications
You must be signed in to change notification settings - Fork 7
/
params_esim_davis.yaml
255 lines (208 loc) · 6.12 KB
/
params_esim_davis.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
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
###########################
# Initial state estimates #
###########################
p: [0.0, 0.0, 20.0] # [x,y,z]
v: [1.0, 1.0, 0.0] # [x,y,z]
q: [0.0, 1.0, 0.0, 0.0] # [w,x,y,z]
# Initial IMU bias estimates
b_w: [0.0, 0.0, 0.0] # [x,y,z]
b_a: [0.0, 0.0, 0.0] # [x,y,z]
# Initial standard deviation estimates [x,y,z]
sigma_dp: [0.0, 0.0, 0.0] # [m]
sigma_dv: [0.05, 0.05, 0.05] # [m/s]
sigma_dtheta: [3.0, 3.0, 3.0] # [deg]
sigma_dbw: [6.0, 6.0, 6.0] # [deg/s]
sigma_dba: [0.3, 0.3, 0.3] # [m/s^2]
###############
# Calibration #
###############
# Camera calibration for myBags/20160426 bags
cam1_fx: 0.8333333333333333333
cam1_fy: 1.1111111111111111111
cam1_cx: 0.5
cam1_cy: 0.5
cam1_dist_model: FOV
cam1_dist_params: [0.0]
cam1_img_width: 240
cam1_img_height: 180
cam1_q_ic: [1.0, 0.0, 0.0, 0.0] # [w,x,y,z]
cam1_p_ic: [0.0, 0.0, 0.0] # [x,y,z]
cam1_time_offset: 0.0
#cam2_fx: 0.46513
#cam2_fy: 0.726246
#cam2_cx: 0.499822
#cam2_cy: 0.458086
#cam2_s: 0.950711
#cam2_dist_model: FOV
#cam2_dist_params: [ 0.950711 ]
#cam2_img_width: 752
#cam2_img_height: 480
#cam2_q_ic: [-0.004059133072894, 0.928890463133302, 0.370065735566358, -0.014049352983967] # [w,x,y,z]
#cam2_p_ic: [-0.05914814, 0.04309647, -0.03085167] # [x,y,z]
#cam2_time_offset: -0.00397400522578
# Feature noise (normalized coordinate standard deviation)
sigma_img: 0.02541924711215672 # sqrt(0.00012922762474977756 * 5.0)
#######
# IMU #
#######
# MXR9500G/M accels (Astec)
n_a: 0.0083 # Accel noise spectral density [m/s^2/sqrt(Hz)]
n_ba: 0.00083 # Accel bias random walk [m/s^3/sqrt(Hz)]
# ADXRS610 gyros (Astec)
n_w: 0.0013 # Gyro noise spectral density [rad/s/sqrt(Hz)]
n_bw: 0.00013 # Gyro bias random walk [rad/s^2/sqrt(Hz)]
# Max specific force norm threshold, after which accelerometer readings are detected as spikes. [m/s^2]
a_m_max: 50.0
#######
# LRF #
#######
# Noise (standard deviation in m)
sigma_range: 0.05
##############
# Sun Sensor #
##############
# Currently unused
q_sc: [1.0, 0.0, 0.0, 0.0] # [w,x,y,z]
w_s: [0.0, 0.0, 1.0] # [x,y,z]
###########
# Tracker #
###########
fast_detection_delta: 20
non_max_supp: True
block_half_length: 6
margin: 6
n_feat_min: 400
# RANSAC: 8 / LMEDS: 4 (see OpenCV doc)
outlier_method: 8
# Parameter used for RANSAC. It is the maximum distance from a point to an epipolar line in pixels,
# beyond which the point is considered an outlier and is not used for computing the final fundamental
# matrix. It can be set to something like 1-3, depending on the accuracy of the point localization,
# image resolution, and the image noise.
outlier_param1: 0.3
# Parameter used for the RANSAC or LMedS methods only. It specifies a desirable level of confidence
# (probability) that the estimated matrix is correct.
outlier_param2: 0.99
# 1 <=> no tiling
n_tiles_h: 1
n_tiles_w: 1
max_feat_per_tile: 10000
########
# EKLT #
########
eklt_batch_size: 500
eklt_update_every_n_events: 20
eklt_displacement_px: 0.6
eklt_patch_size: 35
eklt_max_num_iterations: 25
eklt_tracking_quality: 0.7
eklt_bootstrap: "klt"
eklt_lk_window_size: 20
eklt_num_pyramidal_layers: 3
eklt_scale: 4
eklt_display_features: true
eklt_display_feature_id: true
eklt_display_feature_patches: true
eklt_arrow_length: 5
eklt_max_corners: 60
eklt_min_corners: 35
eklt_log_eps: 0.01
eklt_use_linlog_scale: false
eklt_first_image_t: -1
eklt_tracks_file_txt: ""
eklt_patch_timestamp_assignment: latest-event
eklt_enable_outlier_removal: false
eklt_outlier_method: 8
eklt_outlier_param1: 0.6
eklt_outlier_param2: 0.99
eklt_ekf_feature_interpolation: linear-no-limit
eklt_ekf_feature_extrapolation_limit: -1.0
eklt_ekf_update_every_n: -1
eklt_ekf_update_strategy: every-ros-event-message
eklt_ekf_update_timestamp: patches-average
eklt_harris_block_size: 3
eklt_detection_min_distance: 25
eklt_harris_k: 0
eklt_harris_quality_level: 0.3
#########
# HASTE #
#########
haste_tracker_type: haste-correlation-star
haste_patch_size: 31
haste_max_corners: 60
haste_min_corners: 35
haste_bootstrap_from_frames: false
haste_bootstrap_with_unit_length_of: true
haste_enable_outlier_removal: true
haste_outlier_method: 8
haste_outlier_param1: 0.6
haste_outlier_param2: 0.99
haste_ekf_feature_interpolation: nearest-neighbor
haste_ekf_feature_extrapolation_limit: -1.0
haste_ekf_update_every_n: 3200
haste_ekf_update_strategy: every-n-events
haste_ekf_update_timestamp: patches-maximum
haste_harris_block_size: 3
haste_detection_min_distance: 15
haste_harris_k: 0
haste_harris_quality_level: 0.3
##############
# SLAM-MSCKF #
##############
# Number of poses in the sliding window
n_poses_max: 10
# Number of SLAM features
n_slam_features_max: 25
# Initial inverse depth of SLAM features [1/m]
# (default: 1 / (2 * d_min) [Montiel, 2006])
rho_0: 0.05
# Initial standard deviation of SLAM inverse depth [1/m]
# (default: 1 / (4 * d_min) [Montiel, 2006])
sigma_rho_0: 0.025
# Number of IEKF iterations (1 <=> EKF)
iekf_iter: 1
# Minimum baseline to trigger MSCKF measurement (pixels)
msckf_baseline: 15.0
# Minimum track length for a visual feature to be processed
min_track_length: 10
#######
# EKF #
#######
# State buffer size (default: 250 states)
state_buffer_size: 250
# Expected difference between successive IMU sequence IDs.
delta_seq_imu: 1
# Tolerance for how far in the future/past the closest state request can be without returning an invalid state. [s]
state_buffer_time_margin: 0.02
# Gravity vector in world frame [m/s^2]
g: [0.0, 0.0, -9.81] # [x,y,z]
########
# Misc #
########
# Timeout before 3D trajectory disappears in GUI (s)
traj_timeout_gui: 3
# flags to play rosbags
/use_sim_time: True
# Initialize at startup
init_at_startup: False
##########
# Events #
##########
event_cam1_fx: 0.8333333333333333333
event_cam1_fy: 1.1111111111111111111
event_cam1_cx: 0.5
event_cam1_cy: 0.5
event_cam1_dist_model: FOV
event_cam1_dist_params: [0.0]
event_cam1_img_width: 240
event_cam1_img_height: 180
event_cam1_q_ic: [1.0, 0.0, 0.0, 0.0] # [w,x,y,z]
event_cam1_p_ic: [0.0, 0.0, 0.0] # [x,y,z]
event_cam1_time_offset: 0.0
event_accumulation_methode: 0
event_accumulation_period: 0.1
n_events_min: 15000
n_events_max: 40000
n_events_noise_detection_min: 40
noise_event_rate: 20000
event_norm_factor: 4.0
correct_event_motion: False