initial commit

This commit is contained in:
2022-08-05 08:23:25 +03:00
commit 5ecdc6abcf
387 changed files with 3010095 additions and 0 deletions

View File

@@ -0,0 +1,116 @@
%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: false
calib_cam_intrinsics: true
calib_cam_timeoffset: true
max_clones: 11
max_slam: 50
max_slam_in_update: 25
max_msckf_in_update: 30
dt_slam_delay: 2
gravity_mag: 9.81
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.5
zupt_noise_multiplier: 20
zupt_max_disparity: 0.5 # set to 0 for only imu-based
zupt_only_at_beginning: false
# ==================================================================
# ==================================================================
init_window_time: 2.0
init_imu_thresh: 0.0
init_max_disparity: 1.5
init_max_features: 25
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: 20.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-20
init_dyn_bias_g: [0.0, 0.0, 0.0]
init_dyn_bias_a: [0.0, 0.0, 0.0]
# ==================================================================
# ==================================================================
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: 100
fast_threshold: 65
grid_x: 20
grid_y: 20
min_px_dist: 15
knn_ratio: 0.70
track_frequency: 31.0
downsample_cameras: false
multi_threading: true
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: 2
up_msckf_chi2_multipler: 1
up_slam_sigma_px: 2
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"

View File

@@ -0,0 +1,20 @@
%YAML:1.0 # need to specify the file type at the top!
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: 2.0000e-3 # [ m / s^2 / sqrt(Hz) ] ( accel "white noise" )
accelerometer_random_walk: 3.0000e-3 # [ m / s^3 / sqrt(Hz) ]. ( accel bias diffusion )
gyroscope_noise_density: 1.6968e-04 # [ rad / s / sqrt(Hz) ] ( gyro "white noise" )
gyroscope_random_walk: 1.9393e-05 # [ rad / s^2 / sqrt(Hz) ] ( gyro bias diffusion )
# accelerometer_noise_density: 0.1 # [ m / s^2 / sqrt(Hz) ] ( accel "white noise" )
# accelerometer_random_walk: 0.002 # [ m / s^3 / sqrt(Hz) ]. ( accel bias diffusion )
# gyroscope_noise_density: 0.05 # [ rad / s / sqrt(Hz) ] ( gyro "white noise" )
# gyroscope_random_walk: 4.0e-05 # [ rad / s^2 / sqrt(Hz) ] ( gyro bias diffusion )
model: calibrated
rostopic: /snappy_imu
time_offset: 0.0
update_rate: 200.0

View File

@@ -0,0 +1,37 @@
%YAML:1.0 # need to specify the file type at the top!
cam0:
T_cam_imu:
- [-0.024041523213909927, -0.9996640790624955, 0.009681642096550924, 0.02023430742078562]
- [-0.7184527320882621, 0.010542697330412382, -0.6954958830129113, 0.008311861463499775]
- [0.6951601807615744, -0.023676582632001453, -0.7184648512755534, -0.026628438421085154]
- [0.0, 0.0, 0.0, 1.0]
cam_overlaps: [1]
camera_model: pinhole
distortion_coeffs: [-0.017811595366268803, 0.04897078939103475, -0.041363300782847834,
0.011440891936886532]
distortion_model: equidistant
intrinsics: [275.3385453506587, 275.0852058534152, 315.7697752181792, 233.72625444124952]
resolution: [640, 480]
rostopic: /snappy_cam/stereo_l
timeshift_cam_imu: -0.008637511810764048
cam1:
T_cam_imu:
- [-0.004527750456351745, -0.9999560749011355, -0.008206567133703047, -0.05986676424716047]
- [-0.7208238256076104, 0.008951751262681593, -0.6930605158178762, 0.008989928313050033]
- [0.6931035362139012, 0.0027774840496477826, -0.7208326946456712, -0.026595921269512067]
- [0.0, 0.0, 0.0, 1.0]
T_cn_cnm1:
- [0.9996495696908625, -0.0015816259006504233, 0.026424160845286468, -0.07937720055807065]
- [0.0016709946890799124, 0.9999929578963755, -0.0033603473630593734, 0.0005548331594719445]
- [-0.026418659951183095, 0.0034033244279300045, 0.9996451729434878, 0.0005293439870858398]
- [0.0, 0.0, 0.0, 1.0]
cam_overlaps: [0]
camera_model: pinhole
distortion_coeffs: [0.027860492621377443, -0.027723581962855317, 0.0375199775145906,
-0.018152613898714216]
distortion_model: equidistant
intrinsics: [273.2895238376505, 273.35830490745764, 314.60557378520133, 251.0359907029701]
resolution: [640, 480]
rostopic: /snappy_cam/stereo_r
timeshift_cam_imu: -0.008613446015312496