RTABMAP shows black screen in 3D map and the visualizer frames are very laggy.

classic Classic list List threaded Threaded
3 messages Options
Reply | Threaded
Open this post in threaded view
|

RTABMAP shows black screen in 3D map and the visualizer frames are very laggy.

shivam157
Hi, I am using a custom stereo setup and driver for two OAK FFC OV9282 M12 cameras with an OAK FFC 3P. I have calibrated the camera using pinhole functions of OpenCV, and I have received reprojection error of 0.17. I publish images with the same timestamp in a while loop. I changed the header time stamp in frames to the depthai time, and now the time difference is constant between left and right. 0.033 seconds, according to RTABMAP. I am getting good fps of around 25 on left and right frame in ROS 2. The problem I am facing is that I get a black screen in the 3D map of the RTABMAP visualizer with the following messages in the terminal:
[stereo_odometry-1] [WARN] [1721859987.724759669] [rtabmap.stereo_odometry]: The time difference between left and right frames is high (diff=0.033334s, left=26443.584935s, right=26443.551602s). If your left and right cameras are hardware synchronized, use approx_sync:=false. Otherwise, you may want to set approx_sync_max_interval lower than 0.01s to reject spurious bad synchronizations.
[rtabmap_viz-3] [WARN] [1721859988.130394440] [rtabmap.rtabmap_viz]: rtabmap_viz: Did not receive data since 5 seconds! Make sure the input topics are published ("$ ros2 topic hz my_topic") and the timestamps in their header are set. If topics are coming from different computers, make sure the clocks of the computers are synchronized ("ntpdate"). If topics are not published at the same rate, you could increase "sync_queue_size" and/or "topic_queue_size" parameters (current=10 and 1, respectively).
It should work with a 0.033-second difference between the left and right frames. I don't see any points. The command I use to run RTABMAP is:
ros2 launch rtabmap_launch rtabmap.launch.py     rtabmap_args:="--delete_db_on_start --Vis/EstimateOdom true --subscribe_odom_info false --queue_size 30"     stereo:=true     frame_id:=base_link     wait_imu_to_init:=false     left_image_topic:=/left/image_rect     right_image_topic:=/right/image_rect     left_camera_info_topic:=/left/camera_info     right_camera_info_topic:=/right/camera_info approx_sync_max_interval:=0.04     approx_sync:=true > rtabmap_debug8.txt 
I have posted this issue on RTABMAP github issues. The following is the link: Link
Reply | Threaded
Open this post in threaded view
|

Re: RTABMAP shows black screen in 3D map and the visualizer frames are very laggy.

shivam157
This post was updated on .
I forgot to mention that I am running this on a Jetson Orin Nano. Update: I checked Rviz, and I saw local point clouds but no other point clouds except the local point cloud and the last frame point cloud. I saw that when I move my camera, in Rviz I can see new points, but in RTabmapviz I see that the camera feed freezes. Now the fps is consistent at 25 fps. It frequently shows warnings about no image on the topic for 5 seconds. I am not sure why I get that warning because images are getting published. Can RTABMAP work with this setup I have? I have updated my launch command to :
ros2 launch rtabmap_launch rtabmap.launch.py \
    rtabmap_args:="--delete_db_on_start --approx_sync true" \
    stereo:=true \
    frame_id:=base_link \
    wait_imu_to_init:=false \
    left_image_topic:=/left/image_rect \
    right_image_topic:=/right/image_rect \
    left_camera_info_topic:=/left/camera_info \
    right_camera_info_topic:=/right/camera_info \
    approx_sync_max_interval:=0.04 \
    qos:=1 \
    topic_queue_size:=10 \
    sync_queue_size:=50 \
    subscribe_odom_info:=false \
    Vis/EstimateOdom:=true \
    approx_sync:=true
The QoS profile I use is the following:
// Create a custom QoS profile for SLAM stereo image publishers
    rmw_qos_profile_t custom_qos_profile = rmw_qos_profile_default;
    custom_qos_profile.history = RMW_QOS_POLICY_HISTORY_KEEP_LAST;
    custom_qos_profile.depth = 1; // Changed back to 1
    custom_qos_profile.reliability = RMW_QOS_POLICY_RELIABILITY_RELIABLE;
    custom_qos_profile.durability = RMW_QOS_POLICY_DURABILITY_TRANSIENT_LOCAL;

    custom_qos_profile.avoid_ros_namespace_conventions = false;

    // Convert rmw_qos_profile_t to rclcpp::QoS
    auto qos = rclcpp::QoS(rclcpp::QoSInitialization::from_rmw(custom_qos_profile));

    // Use the sensor data QoS profile directly
    // auto qos = rclcpp::QoS(rclcpp::QoSInitialization::from_rmw(rmw_qos_profile_sensor_data));

    rectifLeftImagePub = this->create_publisher<sensor_msgs::msg::Image>(
        "left/image_rect", qos);
Reply | Threaded
Open this post in threaded view
|

Re: RTABMAP shows black screen in 3D map and the visualizer frames are very laggy.

matlabbe
Administrator
You may look at my comment here: https://github.com/introlab/rtabmap_ros/issues/1185#issuecomment-2254258187

33 ms is huge between left and right. It should be under 1 ms. approx_sync_max_interval would need to be set around 0.001 instead. If no images can be sync on rtabmap side, it means the left and right image stamps are too far from each other (make also sure the camera_info are using the same stamps).