Skip to content

Commit 93adc24

Browse files
authored
Merge pull request #337 from rpng/develop_v2.7
Develop v2.7 - IMU Intrinsic Support
2 parents 58afb2d + ef899cd commit 93adc24

File tree

94 files changed

+4785
-908
lines changed

Some content is hidden

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

94 files changed

+4785
-908
lines changed

Doxyfile

+1-1
Original file line numberDiff line numberDiff line change
@@ -1761,7 +1761,7 @@ LATEX_BIB_STYLE = plainnat
17611761
# The default value is: NO.
17621762
# This tag requires that the tag GENERATE_LATEX is set to YES.
17631763

1764-
LATEX_TIMESTAMP = NO
1764+
LATEX_TIMESTAMP = YES
17651765

17661766
#---------------------------------------------------------------------------
17671767
# Configuration options related to the RTF output

ReadMe.md

+3-2
Original file line numberDiff line numberDiff line change
@@ -21,7 +21,7 @@ details on what the system supports.
2121

2222
## News / Events
2323

24-
24+
* **May 11, 2023** - Inertial intrinsic support released as part of v2.7 along with a few bug fixes and improvements to stereo KLT tracking. Please check out the [release page](https://github.com/rpng/open_vins/releases/tag/v2.7) for details.
2525
* **April 15, 2023** - Minor update to v2.6.3 to support incremental feature triangulation of active features for downstream applications, faster zero-velocity update, small bug fixes, some example realsense configurations, and cached fast state prediction. Please check out the [release page](https://github.com/rpng/open_vins/releases/tag/v2.6.3) for details.
2626
* **April 3, 2023** - We have released a monocular plane-aided VINS, termed [ov_plane](https://github.com/rpng/ov_plane), which leverages the OpenVINS project. Both now support the released [Indoor AR Table](https://github.com/rpng/ar_table_dataset) dataset.
2727
* **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) and v2.6.2 [PR#264](https://github.com/rpng/open_vins/pull/264).
@@ -79,6 +79,7 @@ details on what the system supports.
7979
* Camera to IMU transform
8080
* Camera to IMU time offset
8181
* Camera intrinsics
82+
* Inertial intrinsics (including g-sensitivity)
8283
* Environmental SLAM feature
8384
* OpenCV ARUCO tag SLAM features
8485
* Sparse feature SLAM features
@@ -90,7 +91,7 @@ details on what the system supports.
9091
* Masked tracking
9192
* Static and dynamic state initialization
9293
* Zero velocity detection and updates
93-
* Out of the box evaluation on EurocMav, TUM-VI, UZH-FPV, KAIST Urban and VIO datasets
94+
* Out of the box evaluation on EuRocMav, TUM-VI, UZH-FPV, KAIST Urban and other VIO datasets
9495
* Extensive evaluation suite (ATE, RPE, NEES, RMSE, etc..)
9596

9697
## Codebase Extensions

config/euroc_mav/estimator_config.yaml

+4-4
Original file line numberDiff line numberDiff line change
@@ -3,15 +3,15 @@
33
verbosity: "INFO" # ALL, DEBUG, INFO, WARNING, ERROR, SILENT
44

55
use_fej: true # if first-estimate Jacobians should be used (enable for good consistency)
6-
use_imuavg: true # if using discrete integration, if we should average sequential IMU measurements to "smooth" it
7-
use_rk4int: true # if rk4 integration should be used (overrides imu averaging)
8-
6+
integration: "rk4" # discrete, rk4, analytical (if rk4 or analytical used then analytical covariance propagation is used)
97
use_stereo: true # if we have more than 1 camera, if we should try to track stereo constraints between pairs
108
max_cameras: 2 # how many cameras we have 1 = mono, 2 = stereo, >2 = binocular (all mono tracking)
119

1210
calib_cam_extrinsics: true # if the transform between camera and IMU should be optimized R_ItoC, p_CinI
1311
calib_cam_intrinsics: true # if camera intrinsics should be optimized (focal, center, distortion)
1412
calib_cam_timeoffset: true # if timeoffset between camera and IMU should be optimized
13+
calib_imu_intrinsics: false # if imu intrinsics should be calibrated (rotation and skew-scale matrix)
14+
calib_imu_g_sensitivity: false # if gyroscope gravity sensitivity (Tg) should be calibrated
1515

1616
max_clones: 11 # how many clones in the sliding window
1717
max_slam: 50 # number of features in our state vector
@@ -40,7 +40,7 @@ zupt_only_at_beginning: false
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
4242
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)
43+
init_max_features: 50 # how many features to track during initialization (saves on computation)
4444

4545
init_dyn_use: false # if dynamic initialization should be used
4646
init_dyn_mle_opt_calib: false # if we should optimize calibration during intialization (not recommended)

config/euroc_mav/kalibr_imu_chain.yaml

+30-2
Original file line numberDiff line numberDiff line change
@@ -10,7 +10,35 @@ imu0:
1010
accelerometer_random_walk: 3.0000e-3 # [ m / s^3 / sqrt(Hz) ]. ( accel bias diffusion )
1111
gyroscope_noise_density: 1.6968e-04 # [ rad / s / sqrt(Hz) ] ( gyro "white noise" )
1212
gyroscope_random_walk: 1.9393e-05 # [ rad / s^2 / sqrt(Hz) ] ( gyro bias diffusion )
13-
model: calibrated
1413
rostopic: /imu0
1514
time_offset: 0.0
16-
update_rate: 200.0
15+
update_rate: 200.0
16+
# three different modes supported:
17+
# "calibrated" (same as "kalibr"), "kalibr", "rpng"
18+
model: "kalibr"
19+
# how to get from Kalibr imu.yaml result file:
20+
# - Tw is imu0:gyroscopes:M:
21+
# - R_IMUtoGYRO: is imu0:gyroscopes:M:
22+
# - Ta is imu0:accelerometers:M:
23+
# - R_IMUtoACC not used by Kalibr
24+
# - Tg is imu0:gyroscopes:A:
25+
Tw:
26+
- [ 1.0, 0.0, 0.0 ]
27+
- [ 0.0, 1.0, 0.0 ]
28+
- [ 0.0, 0.0, 1.0 ]
29+
R_IMUtoGYRO:
30+
- [ 1.0, 0.0, 0.0 ]
31+
- [ 0.0, 1.0, 0.0 ]
32+
- [ 0.0, 0.0, 1.0 ]
33+
Ta:
34+
- [ 1.0, 0.0, 0.0 ]
35+
- [ 0.0, 1.0, 0.0 ]
36+
- [ 0.0, 0.0, 1.0 ]
37+
R_IMUtoACC:
38+
- [ 1.0, 0.0, 0.0 ]
39+
- [ 0.0, 1.0, 0.0 ]
40+
- [ 0.0, 0.0, 1.0 ]
41+
Tg:
42+
- [ 0.0, 0.0, 0.0 ]
43+
- [ 0.0, 0.0, 0.0 ]
44+
- [ 0.0, 0.0, 0.0 ]

config/kaist/estimator_config.yaml

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

3-
verbosity: "DEBUG" # ALL, DEBUG, INFO, WARNING, ERROR, SILENT
4-
5-
use_fej: true # if we should use first-estimate Jacobians (enable for good consistency)
6-
use_imuavg: true # for our discrete integration, if we should average sequential IMU measurements to "smooth" it
7-
use_rk4int: true # if rk4 integration should be used (overrides imu averaging)
3+
verbosity: "INFO" # ALL, DEBUG, INFO, WARNING, ERROR, SILENT
84

5+
use_fej: true # if first-estimate Jacobians should be used (enable for good consistency)
6+
integration: "rk4" # discrete, rk4, analytical (if rk4 or analytical used then analytical covariance propagation is used)
97
use_stereo: true # if we have more than 1 camera, if we should try to track stereo constraints
10-
max_cameras: 2
8+
max_cameras: 2 # how many cameras we have 1 = mono, 2 = stereo, >2 = binocular (all mono tracking)
119

1210
calib_cam_extrinsics: false # degenerate motion
1311
calib_cam_intrinsics: true
1412
calib_cam_timeoffset: true # degenerate motion
13+
calib_imu_intrinsics: false
14+
calib_imu_g_sensitivity: false
1515

1616
max_clones: 11
1717
max_slam: 50
@@ -40,7 +40,7 @@ zupt_only_at_beginning: false
4040
init_window_time: 2.0
4141
init_imu_thresh: 0.5
4242
init_max_disparity: 1.5
43-
init_max_features: 75
43+
init_max_features: 50
4444

4545
init_dyn_use: true
4646
init_dyn_mle_opt_calib: false

config/kaist/kalibr_imu_chain.yaml

+30-2
Original file line numberDiff line numberDiff line change
@@ -18,7 +18,35 @@ imu0:
1818
accelerometer_random_walk: 1.0000e-04 # [ m / s^3 / sqrt(Hz) ]. ( accel bias diffusion )
1919
gyroscope_noise_density: 1.7453e-04 # [ rad / s / sqrt(Hz) ] ( gyro "white noise" )
2020
gyroscope_random_walk: 1.0000e-05 # [ rad / s^2 / sqrt(Hz) ] ( gyro bias diffusion )
21-
model: calibrated
2221
rostopic: /imu/data_raw
2322
time_offset: 0.0
24-
update_rate: 500.0
23+
update_rate: 500.0
24+
# three different modes supported:
25+
# "calibrated" (same as "kalibr"), "kalibr", "rpng"
26+
model: "kalibr"
27+
# how to get from Kalibr imu.yaml result file:
28+
# - Tw is imu0:gyroscopes:M:
29+
# - R_IMUtoGYRO: is imu0:gyroscopes:M:
30+
# - Ta is imu0:accelerometers:M:
31+
# - R_IMUtoACC not used by Kalibr
32+
# - Tg is imu0:gyroscopes:A:
33+
Tw:
34+
- [ 1.0, 0.0, 0.0 ]
35+
- [ 0.0, 1.0, 0.0 ]
36+
- [ 0.0, 0.0, 1.0 ]
37+
R_IMUtoGYRO:
38+
- [ 1.0, 0.0, 0.0 ]
39+
- [ 0.0, 1.0, 0.0 ]
40+
- [ 0.0, 0.0, 1.0 ]
41+
Ta:
42+
- [ 1.0, 0.0, 0.0 ]
43+
- [ 0.0, 1.0, 0.0 ]
44+
- [ 0.0, 0.0, 1.0 ]
45+
R_IMUtoACC:
46+
- [ 1.0, 0.0, 0.0 ]
47+
- [ 0.0, 1.0, 0.0 ]
48+
- [ 0.0, 0.0, 1.0 ]
49+
Tg:
50+
- [ 0.0, 0.0, 0.0 ]
51+
- [ 0.0, 0.0, 0.0 ]
52+
- [ 0.0, 0.0, 0.0 ]

config/kaist_vio/estimator_config.yaml

+4-4
Original file line numberDiff line numberDiff line change
@@ -3,15 +3,15 @@
33
verbosity: "INFO" # ALL, DEBUG, INFO, WARNING, ERROR, SILENT
44

55
use_fej: true # if first-estimate Jacobians should be used (enable for good consistency)
6-
use_imuavg: true # if using discrete integration, if we should average sequential IMU measurements to "smooth" it
7-
use_rk4int: true # if rk4 integration should be used (overrides imu averaging)
8-
6+
integration: "rk4" # discrete, rk4, analytical (if rk4 or analytical used then analytical covariance propagation is used)
97
use_stereo: true # NEED TO USE STEREO! OTHERWISE CAN'T RECOVER SCALE!!!!!! DEGENERATE MOTION!!!
108
max_cameras: 2 # NEED TO USE STEREO! OTHERWISE CAN'T RECOVER SCALE!!!!!! DEGENERATE MOTION!!!
119

1210
calib_cam_extrinsics: false # disable since this is a degenerate motion
1311
calib_cam_intrinsics: true
1412
calib_cam_timeoffset: false # disable since this is a degenerate motion
13+
calib_imu_intrinsics: false
14+
calib_imu_g_sensitivity: false
1515

1616
max_clones: 11 # how many clones in the sliding window
1717
max_slam: 50 # number of features in our state vector
@@ -40,7 +40,7 @@ zupt_only_at_beginning: false
4040
init_window_time: 2.0 # how many seconds to collect initialization information
4141
init_imu_thresh: 0.60 # threshold for variance of the accelerometer to detect a "jerk" in motion
4242
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)
43+
init_max_features: 50 # how many features to track during initialization (saves on computation)
4444

4545
init_dyn_use: false
4646
init_dyn_mle_opt_calib: false

config/kaist_vio/kalibr_imu_chain.yaml

+30-2
Original file line numberDiff line numberDiff line change
@@ -14,7 +14,35 @@ imu0:
1414
accelerometer_random_walk: 0.009 # [ m / s^3 / sqrt(Hz) ]. ( accel bias diffusion )
1515
gyroscope_noise_density: 0.001 # [ rad / s / sqrt(Hz) ] ( gyro "white noise" )
1616
gyroscope_random_walk: 0.0003 # [ rad / s^2 / sqrt(Hz) ] ( gyro bias diffusion )
17-
model: calibrated
1817
rostopic: /mavros/imu/data
1918
time_offset: 0.0
20-
update_rate: 100.0
19+
update_rate: 100.0
20+
# three different modes supported:
21+
# "calibrated" (same as "kalibr"), "kalibr", "rpng"
22+
model: "kalibr"
23+
# how to get from Kalibr imu.yaml result file:
24+
# - Tw is imu0:gyroscopes:M:
25+
# - R_IMUtoGYRO: is imu0:gyroscopes:M:
26+
# - Ta is imu0:accelerometers:M:
27+
# - R_IMUtoACC not used by Kalibr
28+
# - Tg is imu0:gyroscopes:A:
29+
Tw:
30+
- [ 1.0, 0.0, 0.0 ]
31+
- [ 0.0, 1.0, 0.0 ]
32+
- [ 0.0, 0.0, 1.0 ]
33+
R_IMUtoGYRO:
34+
- [ 1.0, 0.0, 0.0 ]
35+
- [ 0.0, 1.0, 0.0 ]
36+
- [ 0.0, 0.0, 1.0 ]
37+
Ta:
38+
- [ 1.0, 0.0, 0.0 ]
39+
- [ 0.0, 1.0, 0.0 ]
40+
- [ 0.0, 0.0, 1.0 ]
41+
R_IMUtoACC:
42+
- [ 1.0, 0.0, 0.0 ]
43+
- [ 0.0, 1.0, 0.0 ]
44+
- [ 0.0, 0.0, 1.0 ]
45+
Tg:
46+
- [ 0.0, 0.0, 0.0 ]
47+
- [ 0.0, 0.0, 0.0 ]
48+
- [ 0.0, 0.0, 0.0 ]

config/rpng_aruco/estimator_config.yaml

+6-6
Original file line numberDiff line numberDiff line change
@@ -2,16 +2,16 @@
22

33
verbosity: "INFO" # ALL, DEBUG, INFO, WARNING, ERROR, SILENT
44

5-
use_fej: true # if we should use first-estimate Jacobians (enable for good consistency)
6-
use_imuavg: true # for our discrete integration, if we should average sequential IMU measurements to "smooth" it
7-
use_rk4int: true # if rk4 integration should be used (overrides imu averaging)
8-
5+
use_fej: true # if first-estimate Jacobians should be used (enable for good consistency)
6+
integration: "rk4" # discrete, rk4, analytical (if rk4 or analytical used then analytical covariance propagation is used)
97
use_stereo: true # if we have more than 1 camera, if we should try to track stereo constraints
10-
max_cameras: 2
8+
max_cameras: 2 # how many cameras we have 1 = mono, 2 = stereo, >2 = binocular (all mono tracking)
119

1210
calib_cam_extrinsics: true
1311
calib_cam_intrinsics: true
1412
calib_cam_timeoffset: true
13+
calib_imu_intrinsics: false
14+
calib_imu_g_sensitivity: false
1515

1616
max_clones: 11
1717
max_slam: 50
@@ -40,7 +40,7 @@ zupt_only_at_beginning: true
4040
init_window_time: 2.0
4141
init_imu_thresh: 1.2
4242
init_max_disparity: 2.0
43-
init_max_features: 75
43+
init_max_features: 50
4444

4545
init_dyn_use: false
4646
init_dyn_mle_opt_calib: false

config/rpng_aruco/kalibr_imu_chain.yaml

+30-2
Original file line numberDiff line numberDiff line change
@@ -10,7 +10,35 @@ imu0:
1010
accelerometer_random_walk: 3.0000e-3 # [ m / s^3 / sqrt(Hz) ]. ( accel bias diffusion )
1111
gyroscope_noise_density: 1.6968e-04 # [ rad / s / sqrt(Hz) ] ( gyro "white noise" )
1212
gyroscope_random_walk: 1.9393e-05 # [ rad / s^2 / sqrt(Hz) ] ( gyro bias diffusion )
13-
model: calibrated
1413
rostopic: /imu0
1514
time_offset: 0.0
16-
update_rate: 200.0
15+
update_rate: 200.0
16+
# three different modes supported:
17+
# "calibrated" (same as "kalibr"), "kalibr", "rpng"
18+
model: "kalibr"
19+
# how to get from Kalibr imu.yaml result file:
20+
# - Tw is imu0:gyroscopes:M:
21+
# - R_IMUtoGYRO: is imu0:gyroscopes:M:
22+
# - Ta is imu0:accelerometers:M:
23+
# - R_IMUtoACC not used by Kalibr
24+
# - Tg is imu0:gyroscopes:A:
25+
Tw:
26+
- [ 1.0, 0.0, 0.0 ]
27+
- [ 0.0, 1.0, 0.0 ]
28+
- [ 0.0, 0.0, 1.0 ]
29+
R_IMUtoGYRO:
30+
- [ 1.0, 0.0, 0.0 ]
31+
- [ 0.0, 1.0, 0.0 ]
32+
- [ 0.0, 0.0, 1.0 ]
33+
Ta:
34+
- [ 1.0, 0.0, 0.0 ]
35+
- [ 0.0, 1.0, 0.0 ]
36+
- [ 0.0, 0.0, 1.0 ]
37+
R_IMUtoACC:
38+
- [ 1.0, 0.0, 0.0 ]
39+
- [ 0.0, 1.0, 0.0 ]
40+
- [ 0.0, 0.0, 1.0 ]
41+
Tg:
42+
- [ 0.0, 0.0, 0.0 ]
43+
- [ 0.0, 0.0, 0.0 ]
44+
- [ 0.0, 0.0, 0.0 ]

config/rpng_ironsides/estimator_config.yaml

+6-6
Original file line numberDiff line numberDiff line change
@@ -2,16 +2,16 @@
22

33
verbosity: "INFO" # ALL, DEBUG, INFO, WARNING, ERROR, SILENT
44

5-
use_fej: true # if we should use first-estimate Jacobians (enable for good consistency)
6-
use_imuavg: true # for our discrete integration, if we should average sequential IMU measurements to "smooth" it
7-
use_rk4int: true # if rk4 integration should be used (overrides imu averaging)
8-
5+
use_fej: true # if first-estimate Jacobians should be used (enable for good consistency)
6+
integration: "rk4" # discrete, rk4, analytical (if rk4 or analytical used then analytical covariance propagation is used)
97
use_stereo: true # if we have more than 1 camera, if we should try to track stereo constraints
10-
max_cameras: 2
8+
max_cameras: 2 # how many cameras we have 1 = mono, 2 = stereo, >2 = binocular (all mono tracking)
119

1210
calib_cam_extrinsics: false # degenerate motion
1311
calib_cam_intrinsics: true
1412
calib_cam_timeoffset: false # degenerate motion
13+
calib_imu_intrinsics: false
14+
calib_imu_g_sensitivity: false
1515

1616
max_clones: 11
1717
max_slam: 50
@@ -40,7 +40,7 @@ zupt_only_at_beginning: false
4040
init_window_time: 2.0
4141
init_imu_thresh: 0.5
4242
init_max_disparity: 1.5
43-
init_max_features: 75
43+
init_max_features: 50
4444

4545
init_dyn_use: false
4646
init_dyn_mle_opt_calib: false

config/rpng_ironsides/kalibr_imu_chain.yaml

+30-2
Original file line numberDiff line numberDiff line change
@@ -10,7 +10,35 @@ imu0:
1010
accelerometer_random_walk: 1.3054568211204843e-04 # [ m / s^3 / sqrt(Hz) ]. ( accel bias diffusion )
1111
gyroscope_noise_density: 1.1186830841306218e-04 # [ rad / s / sqrt(Hz) ] ( gyro "white noise" )
1212
gyroscope_random_walk: 8.997530210630026e-07 # [ rad / s^2 / sqrt(Hz) ] ( gyro bias diffusion )
13-
model: calibrated
1413
rostopic: /imu0
1514
time_offset: 0.0
16-
update_rate: 200.0
15+
update_rate: 200.0
16+
# three different modes supported:
17+
# "calibrated" (same as "kalibr"), "kalibr", "rpng"
18+
model: "kalibr"
19+
# how to get from Kalibr imu.yaml result file:
20+
# - Tw is imu0:gyroscopes:M:
21+
# - R_IMUtoGYRO: is imu0:gyroscopes:M:
22+
# - Ta is imu0:accelerometers:M:
23+
# - R_IMUtoACC not used by Kalibr
24+
# - Tg is imu0:gyroscopes:A:
25+
Tw:
26+
- [ 1.0, 0.0, 0.0 ]
27+
- [ 0.0, 1.0, 0.0 ]
28+
- [ 0.0, 0.0, 1.0 ]
29+
R_IMUtoGYRO:
30+
- [ 1.0, 0.0, 0.0 ]
31+
- [ 0.0, 1.0, 0.0 ]
32+
- [ 0.0, 0.0, 1.0 ]
33+
Ta:
34+
- [ 1.0, 0.0, 0.0 ]
35+
- [ 0.0, 1.0, 0.0 ]
36+
- [ 0.0, 0.0, 1.0 ]
37+
R_IMUtoACC:
38+
- [ 1.0, 0.0, 0.0 ]
39+
- [ 0.0, 1.0, 0.0 ]
40+
- [ 0.0, 0.0, 1.0 ]
41+
Tg:
42+
- [ 0.0, 0.0, 0.0 ]
43+
- [ 0.0, 0.0, 0.0 ]
44+
- [ 0.0, 0.0, 0.0 ]

0 commit comments

Comments
 (0)