thien94 / orb_slam3_ros_wrapper

A ROS wrapper for ORB-SLAM3. Focus on portability and flexibility.
166 stars 76 forks source link

"Waiting for Image" with .bag recorded data, D435i #25

Closed SashelI closed 1 year ago

SashelI commented 1 year ago

Hi,

I've been trying to test orbslam3 with a pre-recorded .bag with intel realsense D435i. Everything works fine with euroc monoimu data, but not with mine. I have the image data from the topic in rviz, but nothing in OrbSlam3.

Capture d’écran 2022-12-14 170557

Capture d’écran 2022-12-14 170624

You can find every file I use and modified here.

Thanks for your help !

_____

yaml config file (from original ORBSLAM3):

`%YAML:1.0

#--------------------------------------------------------------------------------------------
# Camera Parameters. Adjust them!
#--------------------------------------------------------------------------------------------
File.version: "1.0"

Camera.type: "PinHole"

# Right Camera calibration and distortion parameters (OpenCV)
Camera1.fx: 382.613
Camera1.fy: 382.613
Camera1.cx: 320.183
Camera1.cy: 236.455

# distortion parameters
Camera1.k1: 0.0
Camera1.k2: 0.0
Camera1.p1: 0.0
Camera1.p2: 0.0

# Camera resolution
Camera.width: 640
Camera.height: 480

# Camera frames per second 
Camera.fps: 30

# Color order of the images (0: BGR, 1: RGB. It is ignored if images are grayscale)
Camera.RGB: 1

# Transformation from body-frame (imu) to left camera
IMU.T_b_c1: !!opencv-matrix
   rows: 4
   cols: 4
   dt: f
   data: [1,0,0,-0.005,
         0,1,0,-0.005,
         0,0,1,0.0117,
         0.0, 0.0, 0.0, 1.0]

# Do not insert KFs when recently lost
IMU.InsertKFsWhenLost: 0

# IMU noise (Use those from VINS-mono)
IMU.NoiseGyro: 1e-3 # 2.44e-4 #1e-3 # rad/s^0.5
IMU.NoiseAcc: 1e-2 # 1.47e-3 #1e-2 # m/s^1.5
IMU.GyroWalk: 1e-6 # rad/s^1.5
IMU.AccWalk: 1e-4 # m/s^2.5
IMU.Frequency: 200.0

#--------------------------------------------------------------------------------------------
# ORB Parameters
#--------------------------------------------------------------------------------------------
# ORB Extractor: Number of features per image
ORBextractor.nFeatures: 1250

# ORB Extractor: Scale factor between levels in the scale pyramid   
ORBextractor.scaleFactor: 1.2

# ORB Extractor: Number of levels in the scale pyramid  
ORBextractor.nLevels: 8

# ORB Extractor: Fast threshold
# Image is divided in a grid. At each cell FAST are extracted imposing a minimum response.
# Firstly we impose iniThFAST. If no corners are detected we impose a lower value minThFAST
# You can lower these values if your images have low contrast           
ORBextractor.iniThFAST: 20
ORBextractor.minThFAST: 7

#--------------------------------------------------------------------------------------------
# Atlas Parameters
#--------------------------------------------------------------------------------------------

#System.SaveAtlasToFile: "media/robot/PASASSEZ/"

#--------------------------------------------------------------------------------------------
# Viewer Parameters
#--------------------------------------------------------------------------------------------
Viewer.KeyFrameSize: 0.05
Viewer.KeyFrameLineWidth: 1.0
Viewer.GraphLineWidth: 0.9
Viewer.PointSize: 2.0
Viewer.CameraSize: 0.08
Viewer.CameraLineWidth: 3.0
Viewer.ViewpointX: 0.0
Viewer.ViewpointY: -0.7
Viewer.ViewpointZ: -3.5
Viewer.ViewpointF: 500.0`

Launch file with the same topic that works in Rviz :

<!-- ORB-SLAM3 -->
<node name="orb_slam3_mono_inertial" pkg="orb_slam3_ros_wrapper" type="orb_slam3_ros_wrapper_mono_inertial" output="screen">
    <!-- for D435i dataset -->
    <remap from="/camera/image_raw"         to="/device_0/sensor_1/Color_0/image/data"/>
    <remap from="/imu"                      to="/device_0/sensor_2/Gyro_0/imu/data"/>

    <!-- Parameters for original ORB-SLAM3 -->
    <param name="voc_file"      type="string"   value="$(find orb_slam3_ros_wrapper)/config/ORBvoc.txt" />
    <param name="settings_file" type="string"   value="$(find orb_slam3_ros_wrapper)/config/RealSense_D435i.yaml" />

    <!-- Parameters for ROS -->
    <param name="world_frame_id"    type="string"   value="world" />
    <param name="cam_frame_id"      type="string"   value="camera" />
</node>

<!-- Visualization - RViz-->
<node name="rviz" pkg="rviz" type="rviz" args="-d $(find orb_slam3_ros_wrapper)/config/orb_slam3_with_imu_D435i.rviz" output="screen" />

<node pkg="hector_trajectory_server" type="hector_trajectory_server" name="trajectory_server_orb_slam3" output="screen" ns="orb_slam3_ros" >
    <param name="/target_frame_name" value="/world" />
    <param name="/source_frame_name" value="/camera" />
    <param name="/trajectory_update_rate" value="20.0" />
    <param name="/trajectory_publish_rate" value="20.0" />
</node>
thien94 commented 1 year ago

Hi @SashelI , thanks for using the code.

I am not sure what is the real issue, but here are some ideas to debug:

SashelI commented 1 year ago

Hi @SashelI , thanks for using the code.

I am not sure what is the real issue, but here are some ideas to debug:

  • First, make sure that the camera and IMU ROS topics specified in the launch file are correct.
  • Second, use rqt_graph to visualize the subscriber/publisher connection.
  • Third, note that ORB-SLAM3 mono/mono-inertial node might not start working until some initial movements occur. Hence, if the camera is still static you would not see any outputs from ORB-SLAM3

Thanks, i figured it out : the algorithm needs some specific conditions to initialize correctly, we had not enough mouvements.