Skip to content

Commit

Permalink
Merge pull request #318 from goldbattle/illixr
Browse files Browse the repository at this point in the history
Cleanup some ROS-free install location logic
  • Loading branch information
goldbattle committed Mar 15, 2023
2 parents 7fe8f58 + 0429390 commit d1a0c6d
Show file tree
Hide file tree
Showing 45 changed files with 268,754 additions and 299 deletions.
119 changes: 119 additions & 0 deletions config/rpng_plane/estimator_config.yaml
Original file line number Diff line number Diff line change
@@ -0,0 +1,119 @@
%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: 1 # 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: 25 # 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: 20 # how many MSCKF features to use in the update
dt_slam_delay: 2 # delay before initializing (helps with stability from bad initialization...)

gravity_mag: 9.8065 # magnitude of gravity in this location

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: 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: 0.5 # threshold for variance of the accelerometer to detect a "jerk" in motion
init_max_disparity: 4.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
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.05 # 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: 10.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-12 # 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 # 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 # if true we will use KLT, otherwise use a ORB descriptor + robust matching
num_pts: 200 # number of points (per camera) we will extract and try to track
fast_threshold: 30 # threshold for fast extraction (warning: lower threshs can be expensive)
grid_x: 8 # extraction sub-grid count for horizontal direction (uniform tracking)
grid_y: 8 # extraction sub-grid count for vertical direction (uniform tracking)
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: 31.0 # frequency we will perform feature tracking at (in frames per second / hertz)
downsample_cameras: false # 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

# 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"




16 changes: 16 additions & 0 deletions config/rpng_plane/kalibr_imu_chain.yaml
Original file line number Diff line number Diff line change
@@ -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.00207649074
accelerometer_random_walk: 0.00041327852
gyroscope_noise_density: 0.00020544166
gyroscope_random_walk: 1.110622e-05
model: calibrated
rostopic: /d455/imu
time_offset: 0.0
update_rate: 400
19 changes: 19 additions & 0 deletions config/rpng_plane/kalibr_imucam_chain.yaml
Original file line number Diff line number Diff line change
@@ -0,0 +1,19 @@
%YAML:1.0


cam0:
T_cam_imu:
- [0.9999654398038452, 0.007342326779113337, -0.003899927610975742, -0.027534314618518095]
- [-0.0073452195116216765, 0.9999727585590525, -0.0007279355223411334, -0.0030587146933711722]
- [0.0038944766308488753, 0.0007565561891287445, 0.9999921303062861, -0.023605118842939803]
- [0.0, 0.0, 0.0, 1.0]
cam_overlaps: []
camera_model: pinhole
distortion_coeffs: [-0.045761895748285604, 0.03423951132164367, -0.00040139057556727315, 0.000431371425853453]
distortion_model: radtan
intrinsics: [416.85223429743274, 414.92069080087543, 421.02459311003213, 237.76180565241077]
resolution: [848, 480]
rostopic: /d455/color/image_raw
timeshift_cam_imu: 0.002524377913673846


Loading

0 comments on commit d1a0c6d

Please sign in to comment.