Closed shivamtrip closed 2 days ago
In terms of this run to run variability, this could be some of the code we have to try pick the most stable axis vectors. https://github.com/rpng/open_vins/blob/master/ov_init/src/utils/helper.h#L148-L158
The yaw about the global frame is arbitrarily picked. VINS has 4DoF, so the global xyz and yaw at the start can be arbitrary. The only thing that should be consistent is the direction of gravity (thus roll and pitch). Thus the global frame defined on startup should be gravity aligned run to run. You should expect the change of yaw to be consistent run to run (I hope this is the case).
Got it, this makes sense! Yes, I do see that the change of yaw is consistent run to run, which helps because I can still account for this variability before switching to another frame convention for my project.
Thank you for your quick response! Also, your OpenVINS and VIO tutorial videos on YouTube have been very helpful - thank you very much for that! :)
Hi @goldbattle,
I noticed that my IMU frame orientation changes when I initialize my stereo-IMU system facing one direction v/s another direction 90 degrees yawed apart. Here are two images indicating what I mean -
IMU frame with x-axis aligned to global frame x-axis
IMU frame with x-axis rotated by 90 wrt global frame x-axis
Both screenshots were taken from two different runs of
ov_msckf/subscribe.launch.py
, soon after initial pick-up of my stereo-IMU system. The difference between the two runs was that my system was yawed by 90-degrees after the first run.My question is - What does this depend on? How can I ensure that my IMU frame is consistent wrt to my global frame, regardless of the initial orientation of my system before running
ov_msckf/subscribe.launch.py
? (the IMU frame to global frame transform is consistent at the same respective orientation - tested multiple times).Estimator Config
``` %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) integration: "rk4" # discrete, rk4, analytical (if rk4 or analytical used then analytical covariance propagation is used) 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 calib_imu_intrinsics: true #false # if imu intrinsics should be calibrated (rotation and skew-scale matrix) calib_imu_g_sensitivity: false #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: 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: false zupt_chi2_multipler: 0 # set to 0 for only disp-based zupt_max_velocity: 0.1 zupt_noise_multiplier: 10 zupt_max_disparity: 0.5 # set to 0 for only imu-based zupt_only_at_beginning: false # ================================================================== 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: 10.0 # max disparity to consider the platform stationary (dependent on resolution) init_max_features: 50 # 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: 5 # extraction sub-grid count for horizontal direction (uniform tracking) grid_y: 5 # extraction sub-grid count for vertical direction (uniform tracking) min_px_dist: 15 # 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 mask0: "mask_t265_cam0.png" #relative to current file mask1: "mask_t265_cam1.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" ```
This link contains my IMU bag files for each orientation (20 sec. length each)