-
Notifications
You must be signed in to change notification settings - Fork 1
/
mynteye_d_config.yaml
109 lines (97 loc) · 4.94 KB
/
mynteye_d_config.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
%YAML:1.0
#common parameters
imu_topic: "/mynteye/imu/data_raw"
image_topic: "/mynteye/left/image_mono"
output_path: "/home/myntai/outcome/config/mynteye"
#camera calibration, please replace it with your own calibration file.
#model_type: MEI
#camera_name: camera
#image_width: 1280
#image_height: c
#mirror_parameters:
# xi: 2.1194262525320258
#distortion_parameters:
# k1: -0.30120468139648438
# k2: 0.08044815063476562
# p1: -0.00009918212890625
# p2: 0.00059127807617188
#projection_parameters:
# gamma1: 2192.0393422024795
# gamma2: 2191.4751134374337
# u0: 656.15618896484375000
# v0: 359.16461181640625000
model_type: PINHOLE
camera_name: camera
image_width: 640
image_height: 480
distortion_parameters:
k1: -0.29249572753906250
k2: 0.07487106323242188
p1: -0.00019836425781250
p2: -0.00031661987304688
projection_parameters:
fx: 354.83758544921875000
fy: 354.83068847656250000
cx: 328.50021362304687500
cy: 240.57057189941406250
# Extrinsic parameter between IMU and Camera.
estimate_extrinsic: 0 # 0 Have an accurate extrinsic parameters. We will trust the following imu^R_cam, imu^T_cam, don't change it.
# 1 Have an initial guess about extrinsic parameters. We will optimize around your initial guess.
# 2 Don't know anything about extrinsic parameters. You don't need to give R,T. We will try to calibrate it. Do some rotation movement at beginning.
#If you choose 0 or 1, you should write down the following matrix.
#Rotation from camera frame to imu frame, imu^R_cam
extrinsicRotation: !!opencv-matrix
rows: 3
cols: 3
dt: d
data: [ 0.99996652, 0.00430873, 0.00695718,
0.00434878, -0.99997401, -0.00575128,
0.00693222, 0.00578135, -0.99995926]
#Translation from camera frame to imu frame, imu^T_cam
extrinsicTranslation: !!opencv-matrix
rows: 3
cols: 1
dt: d
data: [-0.04777362,-0.00223731, -0.02160071]
#feature traker paprameters
max_cnt: 150 # max feature number in feature tracking
min_dist: 30 # min distance between two features
freq: 10 # frequence (Hz) of publish tracking result. At least 10Hz for good estimation. If set 0, the frequence will be same as raw image
F_threshold: 1.0 # ransac threshold (pixel)
show_track: 1 # publish tracking image as topic
equalize: 1 # if image is too dark or light, trun on equalize to find enough features
fisheye: 0 # if using fisheye, trun on it. A circle mask will be loaded to remove edge noisy points
#optimization parameters
max_solver_time: 0.04 # max solver itration time (ms), to guarantee real time
max_num_iterations: 8 # max solver itrations, to guarantee real time
keyframe_parallax: 10.0 # keyframe selection threshold (pixel)
#imu parameters The more accurate parameters you provide, the better performance
acc_n: 0.00253 # accelerometer measurement noise standard deviation. #0.599298904976
#acc_n: 0.02024
gyr_n: 0.0291 # gyroscope measurement noise standard deviation. #0.198614898699
#gyr_n: 0.2328
acc_w: 2.04543326912e-05 # accelerometer bias random work noise standard deviation. #0.02
#acc_w: 1.636347e-04
gyr_w: 0.00088056 # gyroscope bias random work noise standard deviation. #4.0e-5
#gyr_w: 0.00704448
#imu parameters The more accurate parameters you provide, the better performance
#acc_n: 7.6509e-02 # accelerometer measurement noise standard deviation. #0.599298904976
#gyr_n: 9.0086e-03 # gyroscope measurement noise standard deviation. #0.198614898699
#acc_w: 5.3271e-02 # accelerometer bias random work noise standard deviation. #0.02
#gyr_w: 5.5379e-05 # gyroscope bias random work noise standard deviation. #4.0e-5
g_norm: 9.806 # gravity magnitude
#loop closure parameters
loop_closure: 0 # start loop closure
load_previous_pose_graph: 0 # load and reuse previous pose graph; load from 'pose_graph_save_path'
fast_relocalization: 0 # useful in real-time and large project
pose_graph_save_path: "/home/myntai/outcome/config/mynteye/pose_graph/" # save and load path
#unsynchronization parameters
estimate_td: 1 # online estimate time offset between camera and imu
td: 0 # initial value of time offset. unit: s. readed image clock + td = real image clock (IMU clock)
#rolling shutter parameters
rolling_shutter: 0 # 0: global shutter camera, 1: rolling shutter camera
rolling_shutter_tr: 0 # unit: s. rolling shutter read out time per frame (from data sheet).
#visualization parameters
save_image: 1 # save image in pose graph for visualization prupose; you can close this function by setting 0
visualize_imu_forward: 0 # output imu forward propogation to achieve low latency and high frequence results
visualize_camera_size: 0.4 # size of camera marker in RVIZ