Re: RTAB-Map launch file for zed2i

Posted by matlabbe on
URL: http://official-rtab-map-forum.206.s1.nabble.com/RTAB-Map-launch-file-for-zed2i-tp10920p10932.html

Hi,

There are a couple of issues make it difficult to get accurate visual odometry.
 * The camera gets occluded, which can cause the algorithm to lose track of the features

 * The depth image has sometime very wrong disparity

Other system issues:
 * The TF looks wrong, so the base_link frame is tilted 90 degs up by visual odometry

Here is an example running rtabmap on that bag. Note that to make it work, you have to remove "vio/map" frame from the bag (to do so, you can use this script):
roslaunch rtabmap_launch rtabmap.launch \
   args:="-d" \
   visual_odometry:=false \
   odom_topic:=/zed2_front/zed_node/odom \
   rgb_topic:=/zed2_front/zed_node/left/image_rect_color \
   camera_info_topic:=/zed2_front/zed_node/left/camera_info \
   depth_topic:=/zed2_front/zed_node/depth/depth_registered \
   frame_id:=base_link \
   approx_sync:=false rgbd_sync:=true \
   approx_rgbd_sync:=false \
   rgb_image_transport:=compressed \
   compressed:=true \
   depth_image_transport:=raw \
   use_sim_time:=true

rosbag play --clock output.bag

There are some jumps caused by camera occlusions and very bad depth:



Here two other examples not using zed odometry, one using RGB-D mode and the other stereo mode:
roslaunch rtabmap_launch rtabmap.launch \
   args:="-d" \
   visual_odometry:=true \
   rgb_topic:=/zed2_front/zed_node/left/image_rect_color \
   camera_info_topic:=/zed2_front/zed_node/left/camera_info \
   depth_topic:=/zed2_front/zed_node/depth/depth_registered \
   frame_id:=zed2_front_base_link \
   approx_sync:=false \
   rgbd_sync:=true approx_rgbd_sync:=false \
   rgb_image_transport:=compressed \
   compressed:=true \
   depth_image_transport:=raw \
   use_sim_time:=true \
   imu_topic:=/zed2_front/zed_node/imu/data \
   wait_imu_to_init:=true

rosbag play --clock tf:=tf_not_used ts_2023_06_23_21h04m38s_one_random_row.bag

roslaunch rtabmap_launch rtabmap.launch \
   args:="-d" \
   stereo:=true \
   visual_odometry:=true \
   left_image_topic:=/zed2_front/zed_node/left/image_rect_color  \
   left_camera_info_topic:=/zed2_front/zed_node/left/camera_info \
   right_image_topic:=/zed2_front/zed_node/right/image_rect_color \
   right_camera_info_topic:=/zed2_front/zed_node/right/camera_info \
   frame_id:=zed2_front_base_link \
   approx_sync:=false \
   rgbd_sync:=true \
   approx_rgbd_sync:=false \
   compressed:=true  \
   use_sim_time:=true \
   imu_topic:=/zed2_front/zed_node/imu/data \
   wait_imu_to_init:=true

rosbag play --clock tf:=tf_not_used ts_2023_06_23_21h04m38s_one_random_row.bag

In both cases, VO gets lost when there is a camera occlusion or when the depth image is very wrong.