%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: 2 # 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: 50 # 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: 40 # 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 feat_rep_msckf: "GLOBAL_3D" feat_rep_slam: "ANCHORED_MSCKF_INVERSE_DEPTH" 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 # 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: 1.5 # threshold for variance of the accelerometer to detect a "jerk" in motion init_max_disparity: 1.5 # max disparity to consider the platform stationary (dependent on resolution) init_max_features: 25 # how many features to track during initialization (saves on computation) init_dyn_mle_opt_calib: false init_dyn_mle_max_iter: 50 init_dyn_mle_max_time: 0.05 init_dyn_mle_max_threads: 6 init_dyn_num_pose: 6 init_dyn_min_deg: 10.0 init_dyn_inflation_ori: 10 init_dyn_inflation_vel: 100 init_dyn_inflation_bg: 10 init_dyn_inflation_ba: 100 init_dyn_min_rec_cond: 1e-12 init_dyn_bias_g: [0.0, 0.0, 0.0] init_dyn_bias_a: [0.0, 0.0, 0.0] # ================================================================== # ================================================================== 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 num_pts: 200 fast_threshold: 20 grid_x: 20 grid_y: 20 min_px_dist: 15 knn_ratio: 0.70 track_frequency: 21.0 downsample_cameras: false # will downsample image in half if true multi_threading: true # if should enable opencv multi threading 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"