129 lines
4.2 KiB
YAML
129 lines
4.2 KiB
YAML
%YAML:1.0 # need to specify the file type at the top!
|
|
|
|
verbosity: "INFO" # ALL, DEBUG, INFO, WARNING, ERROR, SILENT
|
|
|
|
use_fej: true # if we should use first-estimate Jacobians (enable for good consistency)
|
|
use_imuavg: true # for our 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
|
|
max_cameras: 2
|
|
|
|
calib_cam_extrinsics: true
|
|
calib_cam_intrinsics: true
|
|
calib_cam_timeoffset: true
|
|
|
|
max_clones: 11
|
|
max_slam: 50
|
|
max_slam_in_update: 25
|
|
max_msckf_in_update: 10
|
|
dt_slam_delay: 2
|
|
|
|
gravity_mag: 9.81
|
|
|
|
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: 0.5 # set to 0 for only imu-based
|
|
zupt_only_at_beginning: true
|
|
|
|
# ==================================================================
|
|
# ==================================================================
|
|
|
|
init_window_time: 2.0
|
|
init_imu_thresh: 1.0
|
|
init_max_disparity: 1.5
|
|
init_max_features: 15
|
|
|
|
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.5 # 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: 15.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-15 # 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
|
|
record_timing_filepath: "/tmp/traj_timing.txt"
|
|
|
|
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
|
|
num_pts: 250
|
|
fast_threshold: 15
|
|
grid_x: 20
|
|
grid_y: 20
|
|
min_px_dist: 15
|
|
knn_ratio: 0.70
|
|
track_frequency: 21.0
|
|
downsample_cameras: false
|
|
multi_threading: false
|
|
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"
|
|
|
|
|
|
# ==================================================================
|
|
# ==================================================================
|
|
|
|
|
|
sim_seed_state_init: 0
|
|
sim_seed_preturb: 0
|
|
sim_seed_measurements: 0
|
|
sim_do_perturbation: false
|
|
sim_traj_path: "src/open_vins/ov_data/sim/tum_corridor1_512_16_okvis.txt"
|
|
sim_distance_threshold: 1.2
|
|
sim_freq_cam: 10
|
|
sim_freq_imu: 400
|
|
sim_min_feature_gen_dist: 5.0
|
|
sim_max_feature_gen_dist: 7.0
|