Skip to content

Commit 684e845

Browse files
authored
Merge pull request #259 from rpng/develop_v2.6.1
Develop v2.6.1
2 parents bf0ada9 + d6f5ba1 commit 684e845

File tree

119 files changed

+4823
-3611
lines changed

Some content is hidden

Large Commits have some content hidden by default. Use the searchbox below for content that may be hidden.

119 files changed

+4823
-3611
lines changed

.gitignore

+1
Original file line numberDiff line numberDiff line change
@@ -7,3 +7,4 @@ doxgen_generated
77
*.swp
88
*.swo
99
doc
10+
.vscode

ReadMe.md

+2-1
Original file line numberDiff line numberDiff line change
@@ -17,10 +17,11 @@ details on what the system supports.
1717
* Github project page - https://github.com/rpng/open_vins
1818
* Documentation - https://docs.openvins.com/
1919
* Getting started guide - https://docs.openvins.com/getting-started.html
20-
* Publication reference - http://udel.edu/~pgeneva/downloads/papers/c10.pdf
20+
* Publication reference - https://pgeneva.com/downloads/papers/Geneva2020ICRA.pdf
2121

2222
## News / Events
2323

24+
* **July 14, 2022** - Improved feature extraction logic for >100hz tracking, some bug fixes and updated scripts. See v2.6.1 [PR#259](https://github.com/rpng/open_vins/pull/259).
2425
* **March 14, 2022** - Initial dynamic initialization open sourcing, asynchronous subscription to inertial readings and publishing of odometry, support for lower frequency feature tracking. See v2.6 [PR#232](https://github.com/rpng/open_vins/pull/232) for details.
2526
* **December 13, 2021** - New YAML configuration system, ROS2 support, Docker images, robust static initialization based on disparity, internal logging system to reduce verbosity, image transport publishers, dynamic number of features support, and other small fixes. See
2627
v2.5 [PR#209](https://github.com/rpng/open_vins/pull/209) for details.

config/euroc_mav/estimator_config.yaml

+28-27
Original file line numberDiff line numberDiff line change
@@ -27,7 +27,7 @@ feat_rep_aruco: "ANCHORED_MSCKF_INVERSE_DEPTH"
2727

2828
# zero velocity update parameters we can use
2929
# we support either IMU-based or disparity detection.
30-
try_zupt: true
30+
try_zupt: false
3131
zupt_chi2_multipler: 0 # set to 0 for only disp-based
3232
zupt_max_velocity: 0.1
3333
zupt_noise_multiplier: 50
@@ -39,24 +39,25 @@ zupt_only_at_beginning: true
3939

4040
init_window_time: 2.0 # how many seconds to collect initialization information
4141
init_imu_thresh: 1.5 # threshold for variance of the accelerometer to detect a "jerk" in motion
42-
init_max_disparity: 1.5 # max disparity to consider the platform stationary (dependent on resolution)
43-
init_max_features: 25 # how many features to track during initialization (saves on computation)
44-
45-
init_dyn_mle_opt_calib: false
46-
init_dyn_mle_max_iter: 50
47-
init_dyn_mle_max_time: 0.05
48-
init_dyn_mle_max_threads: 6
49-
init_dyn_num_pose: 6
50-
init_dyn_min_deg: 10.0
51-
52-
init_dyn_inflation_ori: 10
53-
init_dyn_inflation_vel: 100
54-
init_dyn_inflation_bg: 10
55-
init_dyn_inflation_ba: 100
56-
init_dyn_min_rec_cond: 1e-12
57-
58-
init_dyn_bias_g: [0.0, 0.0, 0.0]
59-
init_dyn_bias_a: [0.0, 0.0, 0.0]
42+
init_max_disparity: 10.0 # max disparity to consider the platform stationary (dependent on resolution)
43+
init_max_features: 75 # how many features to track during initialization (saves on computation)
44+
45+
init_dyn_use: false # if dynamic initialization should be used
46+
init_dyn_mle_opt_calib: false # if we should optimize calibration during intialization (not recommended)
47+
init_dyn_mle_max_iter: 50 # how many iterations the MLE refinement should use (zero to skip the MLE)
48+
init_dyn_mle_max_time: 0.05 # how many seconds the MLE should be completed in
49+
init_dyn_mle_max_threads: 6 # how many threads the MLE should use
50+
init_dyn_num_pose: 6 # number of poses to use within our window time (evenly spaced)
51+
init_dyn_min_deg: 10.0 # orientation change needed to try to init
52+
53+
init_dyn_inflation_ori: 10 # what to inflate the recovered q_GtoI covariance by
54+
init_dyn_inflation_vel: 100 # what to inflate the recovered v_IinG covariance by
55+
init_dyn_inflation_bg: 10 # what to inflate the recovered bias_g covariance by
56+
init_dyn_inflation_ba: 100 # what to inflate the recovered bias_a covariance by
57+
init_dyn_min_rec_cond: 1e-12 # reciprocal condition number thresh for info inversion
58+
59+
init_dyn_bias_g: [ 0.0, 0.0, 0.0 ] # initial gyroscope bias guess
60+
init_dyn_bias_a: [ 0.0, 0.0, 0.0 ] # initial accelerometer bias guess
6061

6162
# ==================================================================
6263
# ==================================================================
@@ -76,14 +77,14 @@ filepath_gt: "/tmp/ov_groundtruth.txt"
7677

7778
# our front-end feature tracking parameters
7879
# we have a KLT and descriptor based (KLT is better implemented...)
79-
use_klt: true
80-
num_pts: 200
81-
fast_threshold: 20
82-
grid_x: 20
83-
grid_y: 20
84-
min_px_dist: 15
85-
knn_ratio: 0.70
86-
track_frequency: 21.0
80+
use_klt: true # if true we will use KLT, otherwise use a ORB descriptor + robust matching
81+
num_pts: 200 # number of points (per camera) we will extract and try to track
82+
fast_threshold: 20 # threshold for fast extraction (warning: lower threshs can be expensive)
83+
grid_x: 5 # extraction sub-grid count for horizontal direction (uniform tracking)
84+
grid_y: 5 # extraction sub-grid count for vertical direction (uniform tracking)
85+
min_px_dist: 10 # distance between features (features near each other provide less information)
86+
knn_ratio: 0.70 # descriptor knn threshold for the top two descriptor matches
87+
track_frequency: 21.0 # frequency we will perform feature tracking at (in frames per second / hertz)
8788
downsample_cameras: false # will downsample image in half if true
8889
multi_threading: true # if should enable opencv multi threading
8990
histogram_method: "HISTOGRAM" # NONE, HISTOGRAM, CLAHE

config/kaist/estimator_config.yaml

+18-17
Original file line numberDiff line numberDiff line change
@@ -9,17 +9,16 @@ use_rk4int: true # if rk4 integration should be used (overrides imu averaging)
99
use_stereo: true # if we have more than 1 camera, if we should try to track stereo constraints
1010
max_cameras: 2
1111

12-
calib_cam_extrinsics: false
12+
calib_cam_extrinsics: false # degenerate motion
1313
calib_cam_intrinsics: true
14-
calib_cam_timeoffset: true
14+
calib_cam_timeoffset: true # degenerate motion
1515

16-
max_clones: 12
16+
max_clones: 8
1717
max_slam: 50
1818
max_slam_in_update: 25
1919
max_msckf_in_update: 50
2020
dt_slam_delay: 1
2121

22-
#gravity_mag: 9.79858
2322
gravity_mag: 9.81
2423

2524
feat_rep_msckf: "ANCHORED_MSCKF_INVERSE_DEPTH"
@@ -29,7 +28,7 @@ feat_rep_aruco: "ANCHORED_MSCKF_INVERSE_DEPTH"
2928
# zero velocity update parameters we can use
3029
# we support either IMU-based or disparity detection.
3130
try_zupt: true
32-
zupt_chi2_multipler: 1 # set to 0 for only disp-based
31+
zupt_chi2_multipler: 0.25 # set to 0 for only disp-based
3332
zupt_max_velocity: 0.1
3433
zupt_noise_multiplier: 5
3534
zupt_max_disparity: 0.4 # set to 0 for only imu-based
@@ -39,16 +38,17 @@ zupt_only_at_beginning: false
3938
# ==================================================================
4039

4140
init_window_time: 2.0
42-
init_imu_thresh: 0.5 #0.5
41+
init_imu_thresh: 0.5
4342
init_max_disparity: 1.5
44-
init_max_features: 25
43+
init_max_features: 75
4544

45+
init_dyn_use: true
4646
init_dyn_mle_opt_calib: false
4747
init_dyn_mle_max_iter: 50
4848
init_dyn_mle_max_time: 0.05
4949
init_dyn_mle_max_threads: 6
5050
init_dyn_num_pose: 6
51-
init_dyn_min_deg: 0.0 # traj is mostly straight line motion
51+
init_dyn_min_deg: 5.0 # traj is mostly straight line motion
5252

5353
init_dyn_inflation_ori: 10
5454
init_dyn_inflation_vel: 100
@@ -78,18 +78,19 @@ filepath_gt: "/tmp/ov_groundtruth.txt"
7878
# we have a KLT and descriptor based (KLT is better implemented...)
7979
use_klt: true
8080
num_pts: 200
81-
fast_threshold: 50
82-
grid_x: 20
83-
grid_y: 15
84-
min_px_dist: 30
81+
fast_threshold: 30
82+
grid_x: 5
83+
grid_y: 5
84+
min_px_dist: 20
8585
knn_ratio: 0.65
86-
track_frequency: 21.0
86+
track_frequency: 31.0
8787
downsample_cameras: false
8888
multi_threading: true
8989
histogram_method: "HISTOGRAM" # NONE, HISTOGRAM, CLAHE
9090

91-
fi_max_dist: 500
92-
fi_max_baseline: 800
91+
fi_min_dist: 0.25
92+
fi_max_dist: 150.0
93+
fi_max_baseline: 200
9394
fi_max_cond_number: 20000
9495
fi_triangulate_1d: false
9596

@@ -103,9 +104,9 @@ downsize_aruco: true
103104
# ==================================================================
104105

105106
# camera noises and chi-squared threshold multipliers
106-
up_msckf_sigma_px: 1
107+
up_msckf_sigma_px: 1.5
107108
up_msckf_chi2_multipler: 1
108-
up_slam_sigma_px: 1
109+
up_slam_sigma_px: 1.5
109110
up_slam_chi2_multipler: 1
110111
up_aruco_sigma_px: 1
111112
up_aruco_chi2_multipler: 1

config/kaist/kalibr_imu_chain.yaml

+10-9
Original file line numberDiff line numberDiff line change
@@ -1,22 +1,23 @@
11
%YAML:1.0 # need to specify the file type at the top!
22

33

4-
# MTI-100 series converted from data sheet, guess on bias random walk
4+
# MTI-100 series converted from datasheet, guess on bias random walk
55
# https://www.xsens.com/hubfs/Downloads/usermanual/MTi_usermanual.pdf
6+
67
imu0:
78
T_i_b:
89
- [1.0, 0.0, 0.0, 0.0]
910
- [0.0, 1.0, 0.0, 0.0]
1011
- [0.0, 0.0, 1.0, 0.0]
1112
- [0.0, 0.0, 0.0, 1.0]
12-
accelerometer_noise_density: 2.0000e-03 # [ m / s^2 / sqrt(Hz) ] ( accel "white noise" )
13-
accelerometer_random_walk: 3.0000e-03 # [ m / s^3 / sqrt(Hz) ]. ( accel bias diffusion )
14-
gyroscope_noise_density: 1.6968e-04 # [ rad / s / sqrt(Hz) ] ( gyro "white noise" )
15-
gyroscope_random_walk: 1.9393e-05 # [ rad / s^2 / sqrt(Hz) ] ( gyro bias diffusion )
16-
# <param name="gyroscope_noise_density" type="double" value="1.7453e-04" /> <!-- 1.7453e-04 -->
17-
# <param name="gyroscope_random_walk" type="double" value="1.0000e-05" />
18-
# <param name="accelerometer_noise_density" type="double" value="5.8860e-03" /> <!-- 5.8860e-04 -->
19-
# <param name="accelerometer_random_walk" type="double" value="1.0000e-04" />
13+
# accelerometer_noise_density: 2.0000e-03 # [ m / s^2 / sqrt(Hz) ] ( accel "white noise" )
14+
# accelerometer_random_walk: 3.0000e-03 # [ m / s^3 / sqrt(Hz) ]. ( accel bias diffusion )
15+
# gyroscope_noise_density: 1.6968e-04 # [ rad / s / sqrt(Hz) ] ( gyro "white noise" )
16+
# gyroscope_random_walk: 1.9393e-05 # [ rad / s^2 / sqrt(Hz) ] ( gyro bias diffusion )
17+
accelerometer_noise_density: 5.8860e-03 # [ m / s^2 / sqrt(Hz) ] ( accel "white noise" )
18+
accelerometer_random_walk: 1.0000e-04 # [ m / s^3 / sqrt(Hz) ]. ( accel bias diffusion )
19+
gyroscope_noise_density: 1.7453e-04 # [ rad / s / sqrt(Hz) ] ( gyro "white noise" )
20+
gyroscope_random_walk: 1.0000e-05 # [ rad / s^2 / sqrt(Hz) ] ( gyro bias diffusion )
2021
model: calibrated
2122
rostopic: /imu/data_raw
2223
time_offset: 0.0

config/kaist/kalibr_imucam_chain.yaml

+2-1
Original file line numberDiff line numberDiff line change
@@ -13,6 +13,7 @@ cam0:
1313
intrinsics: [8.1690378992770002e+02,8.1156803828490001e+02,6.0850726281690004e+02,2.6347599764440002e+02]
1414
resolution: [1280, 560]
1515
rostopic: /stereo/left/image_raw
16+
1617
cam1:
1718
T_imu_cam: #rotation from camera to IMU R_CtoI, position of camera in IMU p_CinI
1819
- [-0.00768,-0.01509,0.99986,1.73376]
@@ -25,4 +26,4 @@ cam1:
2526
distortion_model: radtan
2627
intrinsics: [8.1378205539589999e+02,8.0852165574269998e+02,6.1386419539320002e+02,2.4941049348650000e+02]
2728
resolution: [1280, 560]
28-
rostopic: /stereo/right/image_raw
29+
rostopic: /stereo/right/image_raw

config/kaist_vio/estimator_config.yaml

+10-9
Original file line numberDiff line numberDiff line change
@@ -16,18 +16,18 @@ calib_cam_timeoffset: false # disable since this is a degenerate motion
1616
max_clones: 11 # how many clones in the sliding window
1717
max_slam: 50 # number of features in our state vector
1818
max_slam_in_update: 25 # update can be split into sequential updates of batches, how many in a batch
19-
max_msckf_in_update: 40 # how many MSCKF features to use in the update
19+
max_msckf_in_update: 50 # how many MSCKF features to use in the update
2020
dt_slam_delay: 1 # delay before initializing (helps with stability from bad initialization...)
2121

2222
gravity_mag: 9.81 # magnitude of gravity in this location
2323

24-
feat_rep_msckf: "GLOBAL_3D"
24+
feat_rep_msckf: "ANCHORED_MSCKF_INVERSE_DEPTH"
2525
feat_rep_slam: "ANCHORED_MSCKF_INVERSE_DEPTH"
2626
feat_rep_aruco: "ANCHORED_MSCKF_INVERSE_DEPTH"
2727

2828
# zero velocity update parameters we can use
2929
# we support either IMU-based or disparity detection.
30-
try_zupt: true
30+
try_zupt: false
3131
zupt_chi2_multipler: 0 # set to 0 for only disp-based
3232
zupt_max_velocity: 0.02
3333
zupt_noise_multiplier: 10
@@ -38,10 +38,11 @@ zupt_only_at_beginning: false
3838
# ==================================================================
3939

4040
init_window_time: 2.0 # how many seconds to collect initialization information
41-
init_imu_thresh: 1.5 # threshold for variance of the accelerometer to detect a "jerk" in motion
42-
init_max_disparity: 0.20 # max disparity to consider the platform stationary (dependent on resolution)
43-
init_max_features: 25 # how many features to track during initialization (saves on computation)
41+
init_imu_thresh: 0.60 # threshold for variance of the accelerometer to detect a "jerk" in motion
42+
init_max_disparity: 5.0 # max disparity to consider the platform stationary (dependent on resolution)
43+
init_max_features: 75 # how many features to track during initialization (saves on computation)
4444

45+
init_dyn_use: false
4546
init_dyn_mle_opt_calib: false
4647
init_dyn_mle_max_iter: 50
4748
init_dyn_mle_max_time: 0.05
@@ -79,11 +80,11 @@ filepath_gt: "/tmp/ov_groundtruth.txt"
7980
use_klt: true
8081
num_pts: 200
8182
fast_threshold: 30
82-
grid_x: 20
83-
grid_y: 20
83+
grid_x: 5
84+
grid_y: 5
8485
min_px_dist: 15
8586
knn_ratio: 0.70
86-
track_frequency: 10.0
87+
track_frequency: 31.0
8788
downsample_cameras: false # will downsample image in half if true
8889
multi_threading: true # if should enable opencv multi threading
8990
histogram_method: "HISTOGRAM" # NONE, HISTOGRAM, CLAHE

config/kaist_vio/kalibr_imu_chain.yaml

+8-8
Original file line numberDiff line numberDiff line change
@@ -6,14 +6,14 @@ imu0:
66
- [0.0, 1.0, 0.0, 0.0]
77
- [0.0, 0.0, 1.0, 0.0]
88
- [0.0, 0.0, 0.0, 1.0]
9-
accelerometer_noise_density: 0.00333388 # [ m / s^2 / sqrt(Hz) ] ( accel "white noise" )
10-
accelerometer_random_walk: 0.00047402 # [ m / s^3 / sqrt(Hz) ]. ( accel bias diffusion )
11-
gyroscope_noise_density: 0.00005770 # [ rad / s / sqrt(Hz) ] ( gyro "white noise" )
12-
gyroscope_random_walk: 0.00001565 # [ rad / s^2 / sqrt(Hz) ] ( gyro bias diffusion )
13-
# accelerometer_noise_density: 0.07 # [ m / s^2 / sqrt(Hz) ] ( accel "white noise" )
14-
# accelerometer_random_walk: 0.009 # [ m / s^3 / sqrt(Hz) ]. ( accel bias diffusion )
15-
# gyroscope_noise_density: 0.001 # [ rad / s / sqrt(Hz) ] ( gyro "white noise" )
16-
# gyroscope_random_walk: 0.0003 # [ rad / s^2 / sqrt(Hz) ] ( gyro bias diffusion )
9+
# accelerometer_noise_density: 0.00333388 # [ m / s^2 / sqrt(Hz) ] ( accel "white noise" )
10+
# accelerometer_random_walk: 0.00047402 # [ m / s^3 / sqrt(Hz) ]. ( accel bias diffusion )
11+
# gyroscope_noise_density: 0.00005770 # [ rad / s / sqrt(Hz) ] ( gyro "white noise" )
12+
# gyroscope_random_walk: 0.00001565 # [ rad / s^2 / sqrt(Hz) ] ( gyro bias diffusion )
13+
accelerometer_noise_density: 0.07 # [ m / s^2 / sqrt(Hz) ] ( accel "white noise" )
14+
accelerometer_random_walk: 0.009 # [ m / s^3 / sqrt(Hz) ]. ( accel bias diffusion )
15+
gyroscope_noise_density: 0.001 # [ rad / s / sqrt(Hz) ] ( gyro "white noise" )
16+
gyroscope_random_walk: 0.0003 # [ rad / s^2 / sqrt(Hz) ] ( gyro bias diffusion )
1717
model: calibrated
1818
rostopic: /mavros/imu/data
1919
time_offset: 0.0

config/rpng_aruco/estimator_config.yaml

+11-10
Original file line numberDiff line numberDiff line change
@@ -27,7 +27,7 @@ feat_rep_aruco: "ANCHORED_MSCKF_INVERSE_DEPTH"
2727

2828
# zero velocity update parameters we can use
2929
# we support either IMU-based or disparity detection.
30-
try_zupt: true
30+
try_zupt: false
3131
zupt_chi2_multipler: 0 # set to 0 for only disp-based
3232
zupt_max_velocity: 0.1
3333
zupt_noise_multiplier: 50
@@ -39,9 +39,10 @@ zupt_only_at_beginning: true
3939

4040
init_window_time: 2.0
4141
init_imu_thresh: 1.2
42-
init_max_disparity: 1.5
43-
init_max_features: 25
42+
init_max_disparity: 2.0
43+
init_max_features: 75
4444

45+
init_dyn_use: false
4546
init_dyn_mle_opt_calib: false
4647
init_dyn_mle_max_iter: 50
4748
init_dyn_mle_max_time: 0.05
@@ -77,9 +78,9 @@ filepath_gt: "/tmp/ov_groundtruth.txt"
7778
use_klt: true
7879
num_pts: 150
7980
fast_threshold: 30
80-
grid_x: 20
81-
grid_y: 20
82-
min_px_dist: 30
81+
grid_x: 5
82+
grid_y: 5
83+
min_px_dist: 20
8384
knn_ratio: 0.85
8485
track_frequency: 21.0
8586
downsample_cameras: false
@@ -96,12 +97,12 @@ downsize_aruco: true
9697
# ==================================================================
9798

9899
# camera noises and chi-squared threshold multipliers
99-
up_msckf_sigma_px: 1
100+
up_msckf_sigma_px: 1.5
100101
up_msckf_chi2_multipler: 1
101-
up_slam_sigma_px: 1
102+
up_slam_sigma_px: 1.5
102103
up_slam_chi2_multipler: 1
103-
up_aruco_sigma_px: 1
104-
up_aruco_chi2_multipler: 8
104+
up_aruco_sigma_px: 2.0
105+
up_aruco_chi2_multipler: 10
105106

106107
# masks for our images
107108
use_mask: false

0 commit comments

Comments
 (0)