Skip to content

Commit

Permalink
Merge remote-tracking branch 'open_source/master' into develop_v2.7
Browse files Browse the repository at this point in the history
  • Loading branch information
goldbattle committed May 9, 2023
2 parents 14211e2 + db026f3 commit e274c65
Show file tree
Hide file tree
Showing 237 changed files with 271,305 additions and 1,594 deletions.
5 changes: 3 additions & 2 deletions .github/workflows/build.yml
Original file line number Diff line number Diff line change
Expand Up @@ -14,7 +14,8 @@ jobs:
uses: actions/checkout@v2
- name: Installing Ceres Solver
run: |
sudo apt-get update
sudo apt-get update -y
sudo apt install -y libunwind-dev
sudo apt-get install -y cmake libgoogle-glog-dev libgflags-dev libatlas-base-dev libeigen3-dev libsuitesparse-dev libceres-dev
# cd ..
# git clone https://ceres-solver.googlesource.com/ceres-solver
Expand All @@ -27,7 +28,7 @@ jobs:
# cd ../../
- name: Configure and Build
run: |
sudo apt-get update
sudo apt-get update -y
sudo apt-get install -y libeigen3-dev libopencv-dev libboost-all-dev
mkdir build
cd build
Expand Down
12 changes: 11 additions & 1 deletion ReadMe.md
Original file line number Diff line number Diff line change
Expand Up @@ -21,7 +21,10 @@ details on what the system supports.

## News / Events

* **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).

* **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.
* **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.
* **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).
* **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.
* **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
v2.5 [PR#209](https://github.com/rpng/open_vins/pull/209) for details.
Expand Down Expand Up @@ -92,6 +95,13 @@ details on what the system supports.

## Codebase Extensions

* **[ov_plane](https://github.com/rpng/ov_plane)** - A real-time monocular visual-inertial odometry (VIO) system which leverages
environmental planes. At the core it presents an efficient robust monocular-based plane detection algorithm which does
not require additional sensing modalities such as a stereo, depth camera or neural network. The plane detection and tracking
algorithm enables real-time regularization of point features to environmental planes which are either maintained in the state
vector as long-lived planes, or marginalized for efficiency. Planar regularities are applied to both in-state SLAM and
out-of-state MSCKF point features, enabling long-term point-to-plane loop-closures due to the large spacial volume of planes.

* **[vicon2gt](https://github.com/rpng/vicon2gt)** - This utility was created to generate groundtruth trajectories using
a motion capture system (e.g. Vicon or OptiTrack) for use in evaluating visual-inertial estimation systems.
Specifically we calculate the inertial IMU state (full 15 dof) at camera frequency rate and generate a groundtruth
Expand Down
8 changes: 4 additions & 4 deletions config/euroc_mav/estimator_config.yaml
Original file line number Diff line number Diff line change
Expand Up @@ -30,9 +30,9 @@ feat_rep_aruco: "ANCHORED_MSCKF_INVERSE_DEPTH"
try_zupt: false
zupt_chi2_multipler: 0 # set to 0 for only disp-based
zupt_max_velocity: 0.1
zupt_noise_multiplier: 50
zupt_max_disparity: 1.5 # set to 0 for only imu-based
zupt_only_at_beginning: true
zupt_noise_multiplier: 10
zupt_max_disparity: 0.5 # set to 0 for only imu-based
zupt_only_at_beginning: false

# ==================================================================
# ==================================================================
Expand Down Expand Up @@ -86,7 +86,7 @@ min_px_dist: 10 # distance between features (features near each other provide le
knn_ratio: 0.70 # descriptor knn threshold for the top two descriptor matches
track_frequency: 21.0 # frequency we will perform feature tracking at (in frames per second / hertz)
downsample_cameras: false # will downsample image in half if true
multi_threading: true # if should enable opencv multi threading
num_opencv_threads: 4 # -1: auto, 0-1: serial, >1: number of threads
histogram_method: "HISTOGRAM" # NONE, HISTOGRAM, CLAHE

# aruco tag tracker for the system
Expand Down
8 changes: 4 additions & 4 deletions config/kaist/estimator_config.yaml
Original file line number Diff line number Diff line change
Expand Up @@ -13,7 +13,7 @@ calib_cam_timeoffset: true # degenerate motion
calib_imu_intrinsics: false
calib_imu_g_sensitivity: false

max_clones: 8
max_clones: 11
max_slam: 50
max_slam_in_update: 25
max_msckf_in_update: 50
Expand All @@ -28,9 +28,9 @@ feat_rep_aruco: "ANCHORED_MSCKF_INVERSE_DEPTH"
# zero velocity update parameters we can use
# we support either IMU-based or disparity detection.
try_zupt: true
zupt_chi2_multipler: 0.25 # set to 0 for only disp-based
zupt_chi2_multipler: 0.5 # set to 0 for only disp-based
zupt_max_velocity: 0.1
zupt_noise_multiplier: 5
zupt_noise_multiplier: 1
zupt_max_disparity: 0.4 # set to 0 for only imu-based
zupt_only_at_beginning: false

Expand Down Expand Up @@ -85,7 +85,7 @@ min_px_dist: 20
knn_ratio: 0.65
track_frequency: 31.0
downsample_cameras: false
multi_threading: true
num_opencv_threads: 4 # -1: auto, 0-1: serial, >1: number of threads
histogram_method: "HISTOGRAM" # NONE, HISTOGRAM, CLAHE

fi_min_dist: 0.25
Expand Down
13 changes: 7 additions & 6 deletions config/kaist/kalibr_imucam_chain.yaml
Original file line number Diff line number Diff line change
Expand Up @@ -2,9 +2,9 @@

cam0:
T_imu_cam: #rotation from camera to IMU R_CtoI, position of camera in IMU p_CinI
- [-0.00413,-0.01966,0.99980,1.73944]
- [-0.99993,-0.01095,-0.00435,0.27803]
- [0.01103,-0.99975,-0.01962,-0.08785]
- [-0.00681,-0.01532,0.99987,1.71239]
- [-0.99998,0.00033,-0.00680,0.24740]
- [-0.00023,-0.99988,-0.01532,-0.11589]
- [0.0, 0.0, 0.0, 1.0]
cam_overlaps: [1]
camera_model: pinhole
Expand All @@ -16,9 +16,9 @@ cam0:

cam1:
T_imu_cam: #rotation from camera to IMU R_CtoI, position of camera in IMU p_CinI
- [-0.00768,-0.01509,0.99986,1.73376]
- [-0.99988,-0.01305,-0.00788,-0.19706]
- [0.01317,-0.99980,-0.01499,-0.08271]
- [-0.01036,-0.01075,0.99990,1.70544]
- [-0.99994,-0.00178,-0.01038,-0.22770]
- [0.00189,-0.99994,-0.01073,-0.11611]
- [0.0, 0.0, 0.0, 1.0]
cam_overlaps: [0]
camera_model: pinhole
Expand All @@ -27,3 +27,4 @@ cam1:
intrinsics: [8.1378205539589999e+02,8.0852165574269998e+02,6.1386419539320002e+02,2.4941049348650000e+02]
resolution: [1280, 560]
rostopic: /stereo/right/image_raw

2 changes: 1 addition & 1 deletion config/kaist_vio/estimator_config.yaml
Original file line number Diff line number Diff line change
Expand Up @@ -86,7 +86,7 @@ min_px_dist: 15
knn_ratio: 0.70
track_frequency: 31.0
downsample_cameras: false # will downsample image in half if true
multi_threading: true # if should enable opencv multi threading
num_opencv_threads: 4 # -1: auto, 0-1: serial, >1: number of threads
histogram_method: "HISTOGRAM" # NONE, HISTOGRAM, CLAHE

fi_max_dist: 10.0
Expand Down
2 changes: 1 addition & 1 deletion config/rpng_aruco/estimator_config.yaml
Original file line number Diff line number Diff line change
Expand Up @@ -84,7 +84,7 @@ min_px_dist: 20
knn_ratio: 0.85
track_frequency: 21.0
downsample_cameras: false
multi_threading: true
num_opencv_threads: 4 # -1: auto, 0-1: serial, >1: number of threads
histogram_method: "HISTOGRAM" # NONE, HISTOGRAM, CLAHE

# aruco tag tracker for the system
Expand Down
6 changes: 3 additions & 3 deletions config/rpng_ironsides/estimator_config.yaml
Original file line number Diff line number Diff line change
Expand Up @@ -84,7 +84,7 @@ min_px_dist: 15
knn_ratio: 0.65
track_frequency: 31.0
downsample_cameras: false
multi_threading: true
num_opencv_threads: 4 # -1: auto, 0-1: serial, >1: number of threads
histogram_method: "HISTOGRAM" # NONE, HISTOGRAM, CLAHE

fi_min_dist: 1.0
Expand Down Expand Up @@ -113,8 +113,8 @@ up_aruco_chi2_multipler: 1

# masks for our images
use_mask: true
mask0: "../../ov_data/masks/ironsides0.png" #relative to current file
mask1: "../../ov_data/masks/ironsides1.png" #relative to current file
mask0: "mask_ironsides0.png" #relative to current file
mask1: "mask_ironsides1.png" #relative to current file

# imu and camera spacial-temporal
# imu config should also have the correct noise values
Expand Down
File renamed without changes
File renamed without changes.
File renamed without changes
File renamed without changes.
119 changes: 119 additions & 0 deletions config/rpng_plane/estimator_config.yaml
Original file line number Diff line number Diff line change
@@ -0,0 +1,119 @@
%YAML:1.0 # need to specify the file type at the top!

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

use_fej: true # if first-estimate Jacobians should be used (enable for good consistency)
use_imuavg: true # if using discrete integration, if we should average sequential IMU measurements to "smooth" it
use_rk4int: true # if rk4 integration should be used (overrides imu averaging)

use_stereo: true # if we have more than 1 camera, if we should try to track stereo constraints between pairs
max_cameras: 1 # how many cameras we have 1 = mono, 2 = stereo, >2 = binocular (all mono tracking)

calib_cam_extrinsics: true # if the transform between camera and IMU should be optimized R_ItoC, p_CinI
calib_cam_intrinsics: true # if camera intrinsics should be optimized (focal, center, distortion)
calib_cam_timeoffset: true # if timeoffset between camera and IMU should be optimized

max_clones: 11 # how many clones in the sliding window
max_slam: 25 # number of features in our state vector
max_slam_in_update: 25 # update can be split into sequential updates of batches, how many in a batch
max_msckf_in_update: 20 # how many MSCKF features to use in the update
dt_slam_delay: 2 # delay before initializing (helps with stability from bad initialization...)

gravity_mag: 9.8065 # magnitude of gravity in this location

feat_rep_msckf: "GLOBAL_3D"
feat_rep_slam: "GLOBAL_3D"
feat_rep_aruco: "GLOBAL_3D"

# zero velocity update parameters we can use
# we support either IMU-based or disparity detection.
try_zupt: false
zupt_chi2_multipler: 0 # set to 0 for only disp-based
zupt_max_velocity: 0.1
zupt_noise_multiplier: 50
zupt_max_disparity: 1.5 # set to 0 for only imu-based
zupt_only_at_beginning: true

# ==================================================================
# ==================================================================

init_window_time: 2.0 # how many seconds to collect initialization information
init_imu_thresh: 0.5 # threshold for variance of the accelerometer to detect a "jerk" in motion
init_max_disparity: 4.0 # max disparity to consider the platform stationary (dependent on resolution)
init_max_features: 75 # how many features to track during initialization (saves on computation)

init_dyn_use: false # if dynamic initialization should be used
init_dyn_mle_opt_calib: false # if we should optimize calibration during intialization (not recommended)
init_dyn_mle_max_iter: 50 # how many iterations the MLE refinement should use (zero to skip the MLE)
init_dyn_mle_max_time: 0.05 # how many seconds the MLE should be completed in
init_dyn_mle_max_threads: 6 # how many threads the MLE should use
init_dyn_num_pose: 6 # number of poses to use within our window time (evenly spaced)
init_dyn_min_deg: 10.0 # orientation change needed to try to init

init_dyn_inflation_ori: 10 # what to inflate the recovered q_GtoI covariance by
init_dyn_inflation_vel: 100 # what to inflate the recovered v_IinG covariance by
init_dyn_inflation_bg: 10 # what to inflate the recovered bias_g covariance by
init_dyn_inflation_ba: 100 # what to inflate the recovered bias_a covariance by
init_dyn_min_rec_cond: 1e-12 # reciprocal condition number thresh for info inversion

init_dyn_bias_g: [ 0.0, 0.0, 0.0 ] # initial gyroscope bias guess
init_dyn_bias_a: [ 0.0, 0.0, 0.0 ] # initial accelerometer bias guess

# ==================================================================
# ==================================================================

record_timing_information: false # if we want to record timing information of the method
record_timing_filepath: "/tmp/traj_timing.txt" # https://docs.openvins.com/eval-timing.html#eval-ov-timing-flame

# if we want to save the simulation state and its diagional covariance
# use this with rosrun ov_eval error_simulation
save_total_state: false
filepath_est: "/tmp/ov_estimate.txt"
filepath_std: "/tmp/ov_estimate_std.txt"
filepath_gt: "/tmp/ov_groundtruth.txt"

# ==================================================================
# ==================================================================

# our front-end feature tracking parameters
# we have a KLT and descriptor based (KLT is better implemented...)
use_klt: true # if true we will use KLT, otherwise use a ORB descriptor + robust matching
num_pts: 200 # number of points (per camera) we will extract and try to track
fast_threshold: 30 # threshold for fast extraction (warning: lower threshs can be expensive)
grid_x: 8 # extraction sub-grid count for horizontal direction (uniform tracking)
grid_y: 8 # extraction sub-grid count for vertical direction (uniform tracking)
min_px_dist: 20 # distance between features (features near each other provide less information)
knn_ratio: 0.70 # descriptor knn threshold for the top two descriptor matches
track_frequency: 31.0 # frequency we will perform feature tracking at (in frames per second / hertz)
downsample_cameras: false # will downsample image in half if true
num_opencv_threads: 4 # -1: auto, 0-1: serial, >1: number of threads
histogram_method: "HISTOGRAM" # NONE, HISTOGRAM, CLAHE

# aruco tag tracker for the system
# DICT_6X6_1000 from https://chev.me/arucogen/
use_aruco: false
num_aruco: 1024
downsize_aruco: true

# ==================================================================
# ==================================================================

# camera noises and chi-squared threshold multipliers
up_msckf_sigma_px: 1
up_msckf_chi2_multipler: 1
up_slam_sigma_px: 1
up_slam_chi2_multipler: 1
up_aruco_sigma_px: 1
up_aruco_chi2_multipler: 1

# masks for our images
use_mask: false

# imu and camera spacial-temporal
# imu config should also have the correct noise values
relative_config_imu: "kalibr_imu_chain.yaml"
relative_config_imucam: "kalibr_imucam_chain.yaml"




16 changes: 16 additions & 0 deletions config/rpng_plane/kalibr_imu_chain.yaml
Original file line number Diff line number Diff line change
@@ -0,0 +1,16 @@
%YAML:1.0

imu0:
T_i_b:
- [1.0, 0.0, 0.0, 0.0]
- [0.0, 1.0, 0.0, 0.0]
- [0.0, 0.0, 1.0, 0.0]
- [0.0, 0.0, 0.0, 1.0]
accelerometer_noise_density: 0.00207649074
accelerometer_random_walk: 0.00041327852
gyroscope_noise_density: 0.00020544166
gyroscope_random_walk: 1.110622e-05
model: calibrated
rostopic: /d455/imu
time_offset: 0.0
update_rate: 400
19 changes: 19 additions & 0 deletions config/rpng_plane/kalibr_imucam_chain.yaml
Original file line number Diff line number Diff line change
@@ -0,0 +1,19 @@
%YAML:1.0


cam0:
T_cam_imu:
- [0.9999654398038452, 0.007342326779113337, -0.003899927610975742, -0.027534314618518095]
- [-0.0073452195116216765, 0.9999727585590525, -0.0007279355223411334, -0.0030587146933711722]
- [0.0038944766308488753, 0.0007565561891287445, 0.9999921303062861, -0.023605118842939803]
- [0.0, 0.0, 0.0, 1.0]
cam_overlaps: []
camera_model: pinhole
distortion_coeffs: [-0.045761895748285604, 0.03423951132164367, -0.00040139057556727315, 0.000431371425853453]
distortion_model: radtan
intrinsics: [416.85223429743274, 414.92069080087543, 421.02459311003213, 237.76180565241077]
resolution: [848, 480]
rostopic: /d455/color/image_raw
timeshift_cam_imu: 0.002524377913673846


10 changes: 5 additions & 5 deletions config/rpng_sim/estimator_config.yaml
Original file line number Diff line number Diff line change
Expand Up @@ -28,11 +28,11 @@ feat_rep_aruco: "GLOBAL_3D"
# zero velocity update parameters we can use
# we support either IMU-based or disparity detection.
try_zupt: false
zupt_chi2_multipler: 0 # set to 0 for only disp-based
zupt_chi2_multipler: 1 # set to 0 for only disp-based
zupt_max_velocity: 0.1
zupt_noise_multiplier: 50
zupt_max_disparity: 0.5 # set to 0 for only imu-based
zupt_only_at_beginning: true
zupt_noise_multiplier: 1
zupt_max_disparity: 0 # set to 0 for only imu-based
zupt_only_at_beginning: false

# ==================================================================
# ==================================================================
Expand Down Expand Up @@ -84,7 +84,7 @@ min_px_dist: 15
knn_ratio: 0.70
track_frequency: 21.0
downsample_cameras: false
multi_threading: false
num_opencv_threads: 4 # -1: auto, 0-1: serial, >1: number of threads
histogram_method: "HISTOGRAM" # NONE, HISTOGRAM, CLAHE

# aruco tag tracker for the system
Expand Down
28 changes: 27 additions & 1 deletion config/rpng_sim/kalibr_imucam_chain.yaml
Original file line number Diff line number Diff line change
Expand Up @@ -25,4 +25,30 @@ cam1:
distortion_model: radtan
intrinsics: [457.587, 456.134, 379.999, 255.238] #fu, fv, cu, cv
resolution: [752, 480]
rostopic: /cam1/image_raw
rostopic: /cam1/image_raw
cam2:
T_imu_cam: #rotation from camera to IMU R_CtoI, position of camera in IMU p_CinI
- [0.0148655429818, -0.999880929698, 0.00414029679422, -0.0216401454975]
- [0.999557249008, 0.0149672133247, 0.025715529948, 0.124676986768]
- [-0.0257744366974, 0.00375618835797, 0.999660727178, 0.00981073058949]
- [0.0, 0.0, 0.0, 1.0]
cam_overlaps: [1]
camera_model: pinhole
distortion_coeffs: [-0.28340811, 0.07395907, 0.00019359, 1.76187114e-05]
distortion_model: radtan
intrinsics: [458.654, 457.296, 367.215, 248.375] #fu, fv, cu, cv
resolution: [752, 480]
rostopic: /cam2/image_raw
cam3:
T_imu_cam: #rotation from camera to IMU R_CtoI, position of camera in IMU p_CinI
- [0.0125552670891, -0.999755099723, 0.0182237714554, -0.0198435579556]
- [0.999598781151, 0.0130119051815, 0.0251588363115, 0.2253689425024]
- [-0.0253898008918, 0.0179005838253, 0.999517347078, 0.00786212447038]
- [0.0, 0.0, 0.0, 1.0]
cam_overlaps: [0]
camera_model: pinhole
distortion_coeffs: [-0.28368365,0.07451284,-0.00010473,-3.55590700e-05]
distortion_model: radtan
intrinsics: [457.587, 456.134, 379.999, 255.238] #fu, fv, cu, cv
resolution: [752, 480]
rostopic: /cam3/image_raw
Loading

0 comments on commit e274c65

Please sign in to comment.