Skip to content

Commit

Permalink
updated (improved) the gazebo bluefox config
Browse files Browse the repository at this point in the history
  • Loading branch information
klaxalk committed Oct 16, 2024
1 parent 91e66b6 commit 7ed1330
Showing 1 changed file with 19 additions and 21 deletions.
Original file line number Diff line number Diff line change
@@ -1,6 +1,6 @@
%YAML:1.0 # need to specify the file type at the top!

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

use_fej: true # if first-estimate Jacobians should be used (enable for good consistency)
integration: "rk4" # discrete, rk4, analytical (if rk4 or analytical used then analytical covariance propagation is used)
Expand All @@ -14,13 +14,15 @@ calib_imu_intrinsics: false # if imu intrinsics should be calibrated (rotation a
calib_imu_g_sensitivity: false # if gyroscope gravity sensitivity (Tg) should be calibrated

max_clones: 11 # how many clones in the sliding window
max_slam: 100 # 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: 50 # how many MSCKF features to use in the update
dt_slam_delay: 3 # delay before initializing (helps with stability from bad initialization...)
max_slam: 20 # number of features in our state vector
max_slam_in_update: 10 # 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: 1 # delay before initializing (helps with stability from bad initialization...)

gravity_mag: 9.81 # magnitude of gravity in this location

fi_max_dist: 200.0

feat_rep_msckf: "GLOBAL_3D"
feat_rep_slam: "ANCHORED_MSCKF_INVERSE_DEPTH"
feat_rep_aruco: "ANCHORED_MSCKF_INVERSE_DEPTH"
Expand All @@ -41,8 +43,8 @@ zupt_only_at_beginning: true

init_window_time: 2.0 # how many seconds to collect initialization information
# init_window_time: 2.0 # how many seconds to collect initialization information
init_imu_thresh: 0.01 # threshold for variance of the accelerometer to detect a "jerk" in motion
init_max_disparity: 10.0 # max disparity to consider the platform stationary (dependent on resolution)
init_imu_thresh: 0.3 # threshold for variance of the accelerometer to detect a "jerk" in motion
init_max_disparity: 2.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
Expand Down Expand Up @@ -81,18 +83,18 @@ 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: 400 # number of points (per camera) we will extract and try to track
num_pts: 50 # number of points (per camera) we will extract and try to track
# num_pts: 200 # number of points (per camera) we will extract and try to track
# fast_threshold: 20 # threshold for fast extraction (warning: lower threshs can be expensive)
fast_threshold: 15 # threshold for fast extraction (warning: lower threshs can be expensive)
grid_x: 5 # extraction sub-grid count for horizontal direction (uniform tracking)
fast_threshold: 35 # threshold for fast extraction (warning: lower threshs can be expensive)
grid_x: 10 # extraction sub-grid count for horizontal direction (uniform tracking)
# grid_y: 5 # extraction sub-grid count for vertical direction (uniform tracking)
grid_y: 3 # extraction sub-grid count for vertical direction (uniform tracking)
grid_y: 5 # extraction sub-grid count for vertical direction (uniform tracking)
# min_px_dist: 10 # distance between features (features near each other provide less information)
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: 100.0 # frequency we will perform feature tracking at (in frames per second / hertz)
downsample_cameras: false # will downsample image in half if true
track_frequency: 50.0 # frequency we will perform feature tracking at (in frames per second / hertz)
downsample_cameras: true # 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

Expand All @@ -109,10 +111,10 @@ 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_msckf_sigma_px: 1.5
up_msckf_chi2_multipler: 1.5
up_slam_sigma_px: 1.5
up_slam_chi2_multipler: 1.5
up_aruco_sigma_px: 1
up_aruco_chi2_multipler: 1

Expand All @@ -123,7 +125,3 @@ use_mask: false
# imu config should also have the correct noise values
relative_config_imu: "kalibr_imu_chain.yaml"
relative_config_imucam: "kalibr_imucam_chain.yaml"




0 comments on commit 7ed1330

Please sign in to comment.