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

UI not running smoothly #1240

Open
jesussanchez12352 opened this issue Nov 22, 2024 · 9 comments
Open

UI not running smoothly #1240

jesussanchez12352 opened this issue Nov 22, 2024 · 9 comments

Comments

@jesussanchez12352
Copy link

When using RTAB MAP with ROS2 and a Realsense D405 camera the UI is not functioning smoothly for me. I am on ubuntu 22.04 with ROS2 humble. The UI is not updating, the Hz of my realsense depth topic is about 16 Hz consistently. Even though this is shown to be generally consistent, I believe this may be an issue tanking the input performance making the UI also run not smoothly. However, are there any other things in RTAB MAP that could be causing this and is there any way to resolve this? I was thinking to port back to ubuntu 20.04 where things are a little more stable. Any other suggestions? (Sorry for bad video quality but github file size limits)

1122.1.mp4
@matlabbe
Copy link
Member

What commands did you use? (to reproduce here)

Is it the binary version? If you built rtabmap from source, you may try this branch #1225

Do you have special DDS config on your machine? or everything is stock ROS2? I got some TF issues using a bad DDS config, the default one should work though.

@jesussanchez12352
Copy link
Author

jesussanchez12352 commented Nov 24, 2024

I was using stock ROS2 Humble. I was also using stock RTAB-MAP ROS2 with the following commands

ros2 launch rtabmap_examples realsense_d400.launch.py
ros2 launch realsense2_camera rs_launch.py align_depth.enable:=true rgb_camera.profile:=640x360x30 depth_module.enable_auto_exposure:=true enable_sync:=true base_frame_id:=camera_link color_frame_id:=camera_color_optical_frame depth_frame_id:=camera_depth_optical_frame

Also this was my launch script. However from any minimal modifications I made to the example I do not believe I should be having any issues.

import os

from ament_index_python.packages import get_package_share_directory
from launch import LaunchDescription
from launch_ros.actions import Node, SetParameter

def generate_launch_description():
    # Parameters for RTAB-Map and Odometry
    parameters = [{
        'frame_id': 'camera_link',
        'subscribe_depth': True,
        'subscribe_odom_info': True,
        'approx_sync': True,  # Allow slight differences in timestamps
        'Mem/IncrementalMemory': 'true',  # Incremental memory enabled for handheld mapping
        'wait_for_transform_duration': 0.5,  # Increase wait time for transforms to avoid extrapolation errors
    }]

    # Remap topics for RealSense D405
    remappings = [
        ('rgb/image', '/camera/camera/color/image_rect_raw'),  # Use rectified RGB image
        ('rgb/camera_info', '/camera/camera/color/camera_info'),  # Camera info for RGB
        ('depth/image', '/camera/camera/aligned_depth_to_color/image_raw')  # Aligned depth image
    ]

    return LaunchDescription([

        # Ensure the IR emitter is enabled
        SetParameter(name='depth_module.emitter_enabled', value=1),

        # Launch RGB-D odometry node for handheld mapping
        Node(
            package='rtabmap_odom',
            executable='rgbd_odometry',
            output='screen',
            parameters=parameters,
            remappings=remappings
        ),

        # Launch RTAB-Map SLAM node
        Node(
            package='rtabmap_slam',
            executable='rtabmap',
            output='screen',
            parameters=parameters,
            remappings=remappings,
            arguments=['-d']  # Start with an empty database (useful for testing)
        ),

        # Launch RTAB-Map visualizer (for visualizing the map in RViz or standalone)
        Node(
            package='rtabmap_viz',
            executable='rtabmap_viz',
            output='screen',
            parameters=parameters,
            remappings=remappings
        ),

    ])
    

As well from my own testing I believe that RTAB-MAP with ROS2 may be somewhat unstable on Ubuntu 22.04. I am unsure whether it is my own graphics driver (CUDA 12.1) or the realsense node. (realsense is known to have some FPS issues) However, even when trying to use RTAB-MAP without hitting any FPS targets on boot the software UI sometimes does not open properly. This includes the window crashing in the first place or certain windows within the program not opening at all. This seems to be more of an issue when using RVIZ as when launched in the launch file RVIZ is opened first and RTAB VIZ seems to take a while to open up. Thought this may also be a relevant topic of conversation.

I have been looking into computer vision as a student for a while RTAB MAP is a really cool program thank you for all you do @matlabbe !

@jesussanchez12352
Copy link
Author

jesussanchez12352 commented Nov 24, 2024

For now I am going to reboot my PC and try to test on Ubuntu 20.04 with ROS2 galactic to see if that's stable there. (never mind I see rolling is no build so im assuming theres not much support for ubuntu 20.04)

@matlabbe
Copy link
Member

If you don't mind, I recommend building ros2 branch from source, there were some new stability updates the past weeks. In particular this one #1206 and this one #1214

sudo apt remove ros-humble-rtabmap*
cd ros2_ws/src
git clone https://github.com/introlab/rtabmap
git clone --branch ros2 https://github.com/introlab/rtabmap_ros
cd ros2_ws
colcon build --cmake-args -DCMAKE_BUILD_TYPE=Release
source install/setup.bash

@jesussanchez12352
Copy link
Author

jesussanchez12352 commented Nov 25, 2024

So I have tried #1206 the RTAB MAP experience is a lot smoother now (an upgrade from 0.04 fps to 2 fps). I am going to attempt the multithreading node. How do I run #1214 do I just use gh pr checkout 1214 in the ROS2 repo branch?

@matlabbe
Copy link
Member

You can checkout this branch: updating_examples_and_readme

Switching qos between 0 and 1 can also give different results. Another tuning is the choice of the DDS algorithm. It seems cyclonedds can be better in some cases, but I didn't find yet a way to properly compare them when using real sensors. To test without changing config system-wide, you can do:

RMW_IMPLEMENTATION=rmw_cyclonedds_cpp ros2 launch rtabmap_launch rtabmap.launch ...

@jesussanchez12352
Copy link
Author

jesussanchez12352 commented Nov 26, 2024

@matlabbe so I built #1225, #1206, and #1214 all from source. All work a lot more smoothly than the current release, however, the most recent PR you suggested (#1225) runs the most stable and the UI is the most smooth. Although the UI is smooth with ROS2 (around 10 FPS with some freezes for about half a second here and there) I have realized that the internal mapping engine is overlaying existing maps onto themselves. This also happens in the point cloud generation. Should I open up another issue for this? Attached is an image and video of this occurring. I came across this multiple times with multiple different objects.
https://github.com/user-attachments/assets/5a64ca47-d4f4-4c26-a4c2-1054786b7c0f

IMG_8506

EDIT: I thought that this may have occurred due to a lighting issue because usually I have good backlight during the day but it is dark out now. I made a setup with very sterile constant lighting and still the mapping is off with #1225. I have not had this issue with the current release
image

@jesussanchez12352
Copy link
Author

You can checkout this branch: updating_examples_and_readme

Switching qos between 0 and 1 can also give different results. Another tuning is the choice of the DDS algorithm. It seems cyclonedds can be better in some cases, but I didn't find yet a way to properly compare them when using real sensors. To test without changing config system-wide, you can do:

RMW_IMPLEMENTATION=rmw_cyclonedds_cpp ros2 launch rtabmap_launch rtabmap.launch ...

Ok I will definitely be checking this out right now

@matlabbe
Copy link
Member

matlabbe commented Dec 2, 2024

The results in the video are kind of expected, in particular with a D400 series using RGB camera. I am more intrigued by this comment:

I have not had this issue with the current release

There should not be any difference, beside less lags, with the newer version. If you can record a rosbag of that sequence and share it, it would be useful to compare the versions in case we added a regression.

ros2 bag record /tf /tf_static /camera/camera/color/image_rect_raw /camera/camera/color/camera_info /camera/camera/aligned_depth_to_color/image_raw

Sign up for free to join this conversation on GitHub. Already have an account? Sign in to comment
Labels
None yet
Projects
None yet
Development

No branches or pull requests

2 participants