Skip to content

Commit

Permalink
added unreal simulation tmux and configs
Browse files Browse the repository at this point in the history
  • Loading branch information
klaxalk committed Apr 12, 2024
1 parent c746190 commit 3342bef
Show file tree
Hide file tree
Showing 16 changed files with 1,489 additions and 0 deletions.
Original file line number Diff line number Diff line change
@@ -0,0 +1,126 @@
%YAML:1.0 # need to specify the file type at the top!

verbosity: "DEBUG" # ALL, DEBUG, INFO, WARNING, ERROR, SILENT

use_fej: true # if first-estimate Jacobians should be used (enable for good consistency)
integration: "rk4" # discrete, rk4, analytical (if rk4 or analytical used then analytical covariance propagation is used)
use_stereo: false # 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
calib_imu_intrinsics: false # if imu intrinsics should be calibrated (rotation and skew-scale matrix)
calib_imu_g_sensitivity: false # if gyroscope gravity sensitivity (Tg) should be calibrated

max_clones: 11 # how many clones in the sliding window
max_slam: 100 # 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: 50 # how many MSCKF features to use in the update
dt_slam_delay: 3 # 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"
# feat_rep_slam: "ANCHORED_FULL_INVERSE_DEPTH"
# feat_rep_aruco: "ANCHORED_FULL_INVERSE_DEPTH"

# 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_window_time: 2.0 # how many seconds to collect initialization information
init_imu_thresh: 0.05 # threshold for variance of the accelerometer to detect a "jerk" in motion
init_max_disparity: 20.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: 400 # number of points (per camera) we will extract and try to track
# num_pts: 200 # number of points (per camera) we will extract and try to track
# fast_threshold: 20 # threshold for fast extraction (warning: lower threshs can be expensive)
fast_threshold: 15 # threshold for fast extraction (warning: lower threshs can be expensive)
grid_x: 5 # extraction sub-grid count for horizontal direction (uniform tracking)
# grid_y: 5 # extraction sub-grid count for vertical direction (uniform tracking)
grid_y: 3 # extraction sub-grid count for vertical direction (uniform tracking)
# min_px_dist: 10 # distance between features (features near each other provide less information)
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: 21.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"




Original file line number Diff line number Diff line change
@@ -0,0 +1,45 @@
%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: 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 )
# rostopic: /uav0/vio/imu
time_offset: 0.0
# update_rate: 200.0
update_rate: 100.0
# three different modes supported:
# "calibrated" (same as "kalibr"), "kalibr", "rpng"
model: "kalibr"
# how to get from Kalibr imu.yaml result file:
# - Tw is imu0:gyroscopes:M:
# - R_IMUtoGYRO: is imu0:gyroscopes:M:
# - Ta is imu0:accelerometers:M:
# - R_IMUtoACC not used by Kalibr
# - Tg is imu0:gyroscopes:A:
Tw:
- [ 1.0, 0.0, 0.0 ]
- [ 0.0, 1.0, 0.0 ]
- [ 0.0, 0.0, 1.0 ]
R_IMUtoGYRO:
- [ 1.0, 0.0, 0.0 ]
- [ 0.0, 1.0, 0.0 ]
- [ 0.0, 0.0, 1.0 ]
Ta:
- [ 1.0, 0.0, 0.0 ]
- [ 0.0, 1.0, 0.0 ]
- [ 0.0, 0.0, 1.0 ]
R_IMUtoACC:
- [ 1.0, 0.0, 0.0 ]
- [ 0.0, 1.0, 0.0 ]
- [ 0.0, 0.0, 1.0 ]
Tg:
- [ 0.0, 0.0, 0.0 ]
- [ 0.0, 0.0, 0.0 ]
- [ 0.0, 0.0, 0.0 ]
Original file line number Diff line number Diff line change
@@ -0,0 +1,15 @@
%YAML:1.0

cam0:
T_imu_cam: #rotation from camera to IMU R_CtoI, position of camera in IMU p_CinI
- [0.0, 0.0, 1.0, 0.107]
- [-1.0, 0.0, 0.0, 0.00]
- [0.0, -1.0, 0.0, -0.02]
- [0.0, 0.0, 0.0, 1.0]
cam_overlaps: [0]
camera_model: pinhole
distortion_coeffs: [0, 0, 0, 0]
distortion_model: equidistant
intrinsics: [369.5, 640, 230.94, 400] #fu, fv, cu, cv
resolution: [1280, 800]
# rostopic: /uav0/vio/camera/image_raw
27 changes: 27 additions & 0 deletions ros_packages/mrs_open_vins_core/launch/simulation_unreal.launch
Original file line number Diff line number Diff line change
@@ -0,0 +1,27 @@
<launch>

<arg name="UAV_NAME" default="$(optenv UAV_NAME uav1)" />

<!-- what config we are going to run (should match folder name) -->
<arg name="config" default="unreal_simulation" /> <!-- euroc_mav, tum_vi, rpng_aruco -->
<arg name="config_path" default="$(find mrs_open_vins_core)/config/$(arg config)/estimator_config.yaml" />

<group ns="$(arg UAV_NAME)">

<node name="republisher" pkg="image_transport" type="republish" args="compressed in:=/$(arg UAV_NAME)/rgbd/image_raw raw out:=/$(arg UAV_NAME)/rgbd/image_raw" output="screen" clear_params="true" required="true" />

<!-- MASTER NODE! -->
<node name="ov_msckf" pkg="ov_msckf" type="run_subscribe_msckf" output="screen" clear_params="true" required="true">

<!-- master configuration object -->
<param name="config_path" type="string" value="$(arg config_path)" />

<!-- topics -->
<param name="topic_imu" type="string" value="/$(arg UAV_NAME)/hw_api/imu" />
<param name="topic_camera0" type="string" value="/$(arg UAV_NAME)/rgbd/image_raw" />

</node>

</group>

</launch>
Original file line number Diff line number Diff line change
@@ -0,0 +1,5 @@
# A timeout between the takeoff being triggered and the UAV actually taking off
# while the timeout is counting down, the takeoff can be aborted by switching off
# the offboard mode.
# default = 5 sec
safety_timeout: 1.0 # [s]
Loading

0 comments on commit 3342bef

Please sign in to comment.