initial commit
This commit is contained in:
123
config/rpng_ironsides/estimator_config.yaml
Normal file
123
config/rpng_ironsides/estimator_config.yaml
Normal file
@@ -0,0 +1,123 @@
|
||||
%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: 12
|
||||
max_slam: 50
|
||||
max_slam_in_update: 25
|
||||
max_msckf_in_update: 50
|
||||
dt_slam_delay: 1
|
||||
|
||||
gravity_mag: 9.80114
|
||||
|
||||
feat_rep_msckf: "ANCHORED_MSCKF_INVERSE_DEPTH"
|
||||
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: 1 # set to 0 for only disp-based
|
||||
zupt_max_velocity: 0.5
|
||||
zupt_noise_multiplier: 10
|
||||
zupt_max_disparity: 0.4 # set to 0 for only imu-based
|
||||
zupt_only_at_beginning: false
|
||||
|
||||
# ==================================================================
|
||||
# ==================================================================
|
||||
|
||||
#init_window_time: 1.0
|
||||
init_window_time: 2.0
|
||||
init_imu_thresh: 0.5
|
||||
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: 0.0 # traj is mostly straight line motion
|
||||
|
||||
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 # traj is mostly straight line motion
|
||||
|
||||
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: 200
|
||||
fast_threshold: 20
|
||||
grid_x: 20
|
||||
grid_y: 20
|
||||
min_px_dist: 20
|
||||
knn_ratio: 0.65
|
||||
track_frequency: 21.0
|
||||
downsample_cameras: false
|
||||
multi_threading: true
|
||||
histogram_method: "CLAHE" # NONE, HISTOGRAM, CLAHE
|
||||
|
||||
fi_max_dist: 150
|
||||
fi_max_baseline: 200
|
||||
fi_max_cond_number: 20000
|
||||
fi_triangulate_1d: false
|
||||
|
||||
# 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: true
|
||||
mask0: "../../ov_data/masks/ironsides0.png" #relative to current file
|
||||
mask1: "../../ov_data/masks/ironsides1.png" #relative to current file
|
||||
|
||||
# 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
config/rpng_ironsides/kalibr_imu_chain.yaml
Normal file
16
config/rpng_ironsides/kalibr_imu_chain.yaml
Normal file
@@ -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.0027052931930236323 # [ m / s^2 / sqrt(Hz) ] ( accel "white noise" )
|
||||
accelerometer_random_walk: 1.3054568211204843e-04 # [ m / s^3 / sqrt(Hz) ]. ( accel bias diffusion )
|
||||
gyroscope_noise_density: 1.1186830841306218e-04 # [ rad / s / sqrt(Hz) ] ( gyro "white noise" )
|
||||
gyroscope_random_walk: 8.997530210630026e-07 # [ rad / s^2 / sqrt(Hz) ] ( gyro bias diffusion )
|
||||
model: calibrated
|
||||
rostopic: /imu0
|
||||
time_offset: 0.0
|
||||
update_rate: 200.0
|
||||
31
config/rpng_ironsides/kalibr_imucam_chain.yaml
Normal file
31
config/rpng_ironsides/kalibr_imucam_chain.yaml
Normal file
@@ -0,0 +1,31 @@
|
||||
%YAML:1.0
|
||||
|
||||
cam0:
|
||||
T_imu_cam: #rotation from camera to IMU R_CtoI, position of camera in IMU p_CinI
|
||||
- [0.99992127, -0.0078594, 0.0097819, -0.05845078]
|
||||
- [0.00784873, 0.99996856, 0.00112822, -0.00728728]
|
||||
- [-0.00979046, -0.00105136, 0.99995152, 0.0623674]
|
||||
- [0.0, 0.0, 0.0, 1.0]
|
||||
cam_overlaps: [1]
|
||||
camera_model: pinhole
|
||||
distortion_coeffs: [-0.03149689493503132, 0.07696336480701078, -0.06608854732019281, 0.019667561645120218]
|
||||
distortion_model: equidistant
|
||||
intrinsics: [276.4850207717928, 278.0310503180516, 314.5836189313042, 240.16980920673427] #fu, fv, cu, cv
|
||||
resolution: [640, 480]
|
||||
rostopic: /cam0/image_raw
|
||||
timeshift_cam_imu: 0.00621
|
||||
|
||||
cam1:
|
||||
T_imu_cam: #rotation from camera to IMU R_CtoI, position of camera in IMU p_CinI
|
||||
- [0.99995933, 0.00327998, 0.00840069, 0.00793529]
|
||||
- [-0.00328309, 0.99999455, 0.000356, -0.00716413]
|
||||
- [-0.00839948, -0.00038357, 0.99996465, 0.06245421]
|
||||
- [0.0, 0.0, 0.0, 1.0]
|
||||
cam_overlaps: [0]
|
||||
camera_model: pinhole
|
||||
distortion_coeffs: [-0.02998039058251529, 0.07202819722706337, -0.06178718820631651, 0.017655045017816777]
|
||||
distortion_model: equidistant
|
||||
intrinsics: [277.960323846132, 279.4348778432714, 322.404194404853, 236.72685252691352] #fu, fv, cu, cv
|
||||
resolution: [640, 480]
|
||||
rostopic: /cam1/image_raw
|
||||
timeshift_cam_imu: 0.00621
|
||||
Reference in New Issue
Block a user