Skip to content
New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

Drift trajectory in open space? #379

Closed
Userpc1010 opened this issue Sep 7, 2023 · 2 comments
Closed

Drift trajectory in open space? #379

Userpc1010 opened this issue Sep 7, 2023 · 2 comments
Labels
user-platform User has trouble running on their own platform.

Comments

@Userpc1010
Copy link

What is the reason for the occurrence of drift in open spaces in various navigation frameworks? I tested 5 different frameworks realtime on the car in different modes (vins-rgb-d mono+rgb-d mode, orb-slam3 rgb-d-inertial, rebivo mono, rtab-map rgb-d, openvins stereo) and everywhere I get a similar result and strong drift effects?

Unfortunately, I could not set up the r-viz visualizer well, the trajectory on the record can be very poorly visible((

https://youtu.be/LlvSzjQ40l4

Rosbag_all_topic_d455

Short_tf_static_rqt

@goldbattle goldbattle added the user-platform User has trouble running on their own platform. label Sep 14, 2023
@goldbattle
Copy link
Member

I am not sure. Do you have the configuration files you used to launch OpenVINS? Does the feature tracking look good? Does this sensor work for general 3D motion for you with good quality?

If you are running on a car dataset, I recommend using a mask to remove features from the dash. See the rpng_ironsides dataset for and example car dataset.

@Userpc1010
Copy link
Author

Userpc1010 commented Sep 14, 2023

My configuration was like this:

estimator_config.yaml:

%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: 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: 50 # 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: 40 # 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: true
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

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



kalibr_imucam_chain.yaml:

%YAML:1.0

cam0:
  T_cam_imu:
    - [0.9999942992129773, -0.0006837030318090254, 0.003306673813320594, 0.01734357246126995]
    - [0.0006819183997666188, 0.9999996212593953, 0.000540803438387852, -0.008519633421954392]
    - [-0.003307042309899398, -0.0005385454736672996, 0.9999943867042107, -0.018723905687986195]
    - [0.0, 0.0, 0.0, 1.0]
  cam_overlaps: [1]
  camera_model: pinhole
  distortion_coeffs: [0.0, 0.0, 0.0, 0.0]
  distortion_model: radtan
  intrinsics: [320.17488748238287, 320.0283628174116, 314.0668795454674, 180.36893447271257]
  resolution: [848, 480]
  rostopic: /d455/infra1/image_rect_raw
  timeshift_cam_imu: 0.004639958649183853

cam1:
  T_cam_imu:
    - [0.9999855287596171, -0.0003605813977934117, 0.00536770457504073, -0.07667191595392714]
    - [0.000365189906339375, 0.9999995655732808, -0.0008576068926449692, -0.008542662389807396]
    - [-0.005367393006074334, 0.0008595547135404881, 0.9999852260198713, -0.017739927010989854]
    - [0.0, 0.0, 0.0, 1.0]
  T_cn_cnm1:
    - [0.9999978238338454, 0.00032423014342537217, 0.0020608741811117422, -0.09397410073693341]
    - [-0.00032135073657469737, 0.9999989720658036, -0.0013973550168239824, -4.36282992379309e-05]
    - [-0.002061325127286215, 0.0013966897125111987, 0.99999690009348, 0.0010315706607051294]
    - [0.0, 0.0, 0.0, 1.0]
  cam_overlaps: [0]
  camera_model: pinhole
  distortion_coeffs: [0.0, 0.0, 0.0, 0.0]
  distortion_model: radtan
  intrinsics: [319.69438067702725, 320.1948319604044, 313.46161305104766, 180.7178241492703]
  resolution: [848, 480]
  rostopic: /d455/infra2/image_rect_raw
  timeshift_cam_imu: 0.005012709485041032
  
#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


launch_d455.example:

<?xml version="1.0" encoding="UTF-8"?>
<launch>
  <arg name="serial_no"           default="215122253909"/>
  <arg name="json_file_path"      default=""/>
  <arg name="camera"              default="d455"/>
  <arg name="tf_prefix"           default="$(arg camera)"/>
  <arg name="external_manager"    default="false"/>
  <arg name="manager"             default="realsense2_camera_manager"/>
  <arg name="respawn"             default="true"/>

  <arg name="fisheye_width"       default="640"/>
  <arg name="fisheye_height"      default="480"/>
  <arg name="enable_fisheye"      default="false"/>

  <arg name="depth_width"         default="848"/>
  <arg name="depth_height"        default="480"/>
  <arg name="enable_depth"        default="false"/>

  <arg name="infra_width"        default="848"/>
  <arg name="infra_height"       default="480"/>
  <arg name="enable_infra1"       default="true"/>
  <arg name="enable_infra2"       default="true"/>

  <arg name="color_width"         default="848"/>
  <arg name="color_height"        default="480"/>
  <arg name="enable_color"        default="false"/>

  <arg name="fisheye_fps"         default="30"/>
  <arg name="depth_fps"           default="30"/>
  <arg name="infra_fps"           default="30"/>
  <arg name="color_fps"           default="30"/>
  <arg name="gyro_fps"            default="200"/>
  <arg name="accel_fps"           default="200"/>
  <arg name="enable_gyro"         default="true"/>
  <arg name="enable_accel"        default="true"/>

  <arg name="enable_pointcloud"         default="false"/>
  <arg name="pointcloud_texture_stream" default="RS2_STREAM_COLOR"/>
  <arg name="pointcloud_texture_index"  default="0"/>

  <arg name="enable_sync"               default="false"/>
  <arg name="align_depth"               default="true"/>

  <arg name="filters"                   default="pointcloud"/>
  <arg name="clip_distance"             default="-2"/>
  <arg name="linear_accel_cov"          default="0.01"/>
  <arg name="initial_reset"             default="false"/>
  <arg name="reconnect_timeout"         default="6.0"/>
  <arg name="unite_imu_method"          default="linear_interpolation"/>
  <arg name="topic_odom_in"             default="odom_in"/>
  <arg name="calib_odom_file"           default=""/>
  <arg name="publish_odom_tf"           default="true"/>
  <arg name="allow_no_texture_points"   default="false"/>

  <group ns="$(arg camera)">
    <include file="$(find realsense2_camera)/launch/includes/nodelet.launch.xml">
      <arg name="tf_prefix"                value="$(arg tf_prefix)"/>
      <arg name="external_manager"         value="$(arg external_manager)"/>
      <arg name="manager"                  value="$(arg manager)"/>
      <arg name="serial_no"                value="$(arg serial_no)"/>
      <arg name="json_file_path"           value="$(arg json_file_path)"/>
      <arg name="respawn"                  value="$(arg respawn)"/>

      <arg name="enable_pointcloud"        value="$(arg enable_pointcloud)"/>
      <arg name="pointcloud_texture_stream" value="$(arg pointcloud_texture_stream)"/>
      <arg name="pointcloud_texture_index"  value="$(arg pointcloud_texture_index)"/>
      <arg name="enable_sync"              value="$(arg enable_sync)"/>
      <arg name="align_depth"              value="$(arg align_depth)"/>

      <arg name="fisheye_width"            value="$(arg fisheye_width)"/>
      <arg name="fisheye_height"           value="$(arg fisheye_height)"/>
      <arg name="enable_fisheye"           value="$(arg enable_fisheye)"/>

      <arg name="depth_width"              value="$(arg depth_width)"/>
      <arg name="depth_height"             value="$(arg depth_height)"/>
      <arg name="enable_depth"             value="$(arg enable_depth)"/>

      <arg name="color_width"              value="$(arg color_width)"/>
      <arg name="color_height"             value="$(arg color_height)"/>
      <arg name="enable_color"             value="$(arg enable_color)"/>

      <arg name="infra_width"              value="$(arg infra_width)"/>
      <arg name="infra_height"             value="$(arg infra_height)"/>
      <arg name="enable_infra1"            value="$(arg enable_infra1)"/>
      <arg name="enable_infra2"            value="$(arg enable_infra2)"/>

      <arg name="fisheye_fps"              value="$(arg fisheye_fps)"/>
      <arg name="depth_fps"                value="$(arg depth_fps)"/>
      <arg name="infra_fps"                value="$(arg infra_fps)"/>
      <arg name="color_fps"                value="$(arg color_fps)"/>
      <arg name="gyro_fps"                 value="$(arg gyro_fps)"/>
      <arg name="accel_fps"                value="$(arg accel_fps)"/>
      <arg name="enable_gyro"              value="$(arg enable_gyro)"/>
      <arg name="enable_accel"             value="$(arg enable_accel)"/>

      <arg name="filters"                  value="$(arg filters)"/>
      <arg name="clip_distance"            value="$(arg clip_distance)"/>
      <arg name="linear_accel_cov"         value="$(arg linear_accel_cov)"/>
      <arg name="initial_reset"            value="$(arg initial_reset)"/>
      <arg name="reconnect_timeout"        value="$(arg reconnect_timeout)"/>
      <arg name="unite_imu_method"         value="$(arg unite_imu_method)"/>
      <arg name="topic_odom_in"            value="$(arg topic_odom_in)"/>
      <arg name="calib_odom_file"          value="$(arg calib_odom_file)"/>
      <arg name="publish_odom_tf"          value="$(arg publish_odom_tf)"/>
      <arg name="allow_no_texture_points"  value="$(arg allow_no_texture_points)"/>
    </include>
  </group>

</launch>

subscribe.launch:

<launch>

    <!-- what config we are going to run (should match folder name) -->
    <arg name="verbosity"   default="INFO" /> <!-- ALL, DEBUG, INFO, WARNING, ERROR, SILENT -->
    <arg name="config"      default="rs_d455" /> <!-- euroc_mav, tum_vi, rpng_aruco -->
    <arg name="config_path" default="$(find ov_msckf)/../config/$(arg config)/estimator_config.yaml" />

    <!-- mono or stereo and what ros bag to play -->
    <arg name="max_cameras" default="2" />
    <arg name="use_stereo"  default="true" />
    <arg name="bag_start"   default="0" /> <!-- v1-2: 0, mh1: 40, mh2: 35, mh3: 17.5, mh4-5: 15 -->
    <arg name="bag_rate"    default="1" />
    <arg name="dataset"     default="V1_01_easy" /> <!-- V1_01_easy, V1_02_medium, V2_02_medium -->
    <arg name="dobag"       default="false" /> <!-- if we should play back the bag -->
    <arg name="bag"         default="/media/patrick/RPNG\ FLASH\ 3/$(arg config)/$(arg dataset).bag" />
<!--    <arg name="bag"         default="/home/patrick/datasets/$(arg config)/$(arg dataset).bag" />-->
<!--    <arg name="bag"         default="/datasets/$(arg config)/$(arg dataset).bag" />-->

    <!-- saving trajectory path and timing information -->
    <arg name="dosave"      default="false" />
    <arg name="dotime"      default="false" />
    <arg name="path_est"    default="/tmp/traj_estimate.txt" />
    <arg name="path_time"   default="/tmp/traj_timing.txt" />

    <!-- if we should viz the groundtruth -->
    <arg name="dolivetraj"  default="false" />
    <arg name="path_gt"     default="$(find ov_data)/$(arg config)/$(arg dataset).txt" />

    <!-- MASTER NODE! -->
<!--    <node name="ov_msckf" pkg="ov_msckf" type="run_subscribe_msckf" output="screen" clear_params="true" required="true" launch-prefix="gdb -ex run &#45;&#45;args">-->
    <node name="ov_msckf" pkg="ov_msckf" type="run_subscribe_msckf" output="screen" clear_params="true" required="true">

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

        <!-- world/filter parameters -->
        <param name="use_stereo"             type="bool"   value="$(arg use_stereo)" />
        <param name="max_cameras"            type="int"    value="$(arg max_cameras)" />

        <!-- timing statistics recording -->
        <param name="record_timing_information"   type="bool"   value="$(arg dotime)" />
        <param name="record_timing_filepath"      type="string" value="$(arg path_time)" />

    </node>

    <!-- play the dataset -->
    <group if="$(arg dobag)">
        <node pkg="rosbag" type="play" name="rosbag" args="-d 1 -r $(arg bag_rate) -s $(arg bag_start) $(arg bag)" required="true"/>
    </group>

    <!-- record the trajectory if enabled -->
    <group if="$(arg dosave)">
        <node name="recorder_estimate" pkg="ov_eval" type="pose_to_file" output="screen" required="true">
            <param name="topic"      type="str" value="/ov_msckf/poseimu" />
            <param name="topic_type" type="str" value="PoseWithCovarianceStamped" />
            <param name="output"     type="str" value="$(arg path_est)" />
        </node>
    </group>

    <!-- path viz of aligned gt -->
    <group if="$(arg dolivetraj)">
        <node name="live_align_trajectory" pkg="ov_eval" type="live_align_trajectory" output="log" clear_params="true">
            <param name="alignment_type" type="str" value="posyaw" />
            <param name="path_gt"        type="str" value="$(arg path_gt)" />
        </node>
    </group>

</launch>

Unfortunately, I did not pay attention to the tracking functions, I mainly focused on the trajectory of the visualizer, but I think this can be reproduced using the ROS bag attached to the message, if your don’t mind checking it out, I’m just starting to understand openvins.

This is a good question, I'm probably not so savvy as to give a definite answer, I used an intel realsense d455 in stereo mode.

Can I make a homemade mask to cover the bonnet? I suppose this will not solve all the problems, for example, the re-reflection of light from the bonnet onto the camera may disrupt the exposure, but unfortunately I do not have a tripod for external mounting of the camera(((.

Sign up for free to join this conversation on GitHub. Already have an account? Sign in to comment
Labels
user-platform User has trouble running on their own platform.
Projects
None yet
Development

No branches or pull requests

2 participants