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

Too Many Unknowns in Map #1244

Open
InDroKalena opened this issue Nov 26, 2024 · 2 comments
Open

Too Many Unknowns in Map #1244

InDroKalena opened this issue Nov 26, 2024 · 2 comments

Comments

@InDroKalena
Copy link

Hello!

I am using RTAB to map an environment in Isaac Sim using a stereo ZED X camera and ROS2. I am getting what I think is a good number of inliers with stereo odom, as shown below, yet my stereo map is largely made up of unknowns. I have included my rtabmap launch file below - please let me know if you have any advice! My colleague suggested that it could be that the environment is too plain, especially with the white floor and walls, but I changed these colours and am still seeing a similar result. Let me know if I can provide any other information to make this issue more clear. Thank you in advance!

image
image

from launch import LaunchDescription
from launch_ros.actions import Node
from launch.substitutions import LaunchConfiguration
from launch.actions import DeclareLaunchArgument

def generate_launch_description():
use_sim_time = LaunchConfiguration('use_sim_time')
rtabmap_args = LaunchConfiguration('rtabmap_args')
database_path = LaunchConfiguration('database_path')
localization = LaunchConfiguration('localization')

return LaunchDescription([
    DeclareLaunchArgument('use_sim_time', default_value='true'),
    DeclareLaunchArgument('rtabmap_args', default_value='--delete_db_on_start'),
    DeclareLaunchArgument('database_path', default_value='/my/path/to/rtabmap.db'),
    DeclareLaunchArgument('localization', default_value='false'),

    Node(
        package='rtabmap_slam',
        executable='rtabmap',
        name='rtabmap',
        output='screen',
        parameters=[{
            'use_sim_time': use_sim_time,
            'frame_id': 'base_footprint',
            'subscribe_depth': False,
            'subscribe_rgb': False,
            'subscribe_stereo': True,
            'visual_odometry': True,
            'approx_sync': False,
            'odom_frame_id': 'odom',
            'stereo_approx_sync': False,
            'stereo_namespace': '/zed/zed_node',
            'imu_topic': '/zed/zed_node/imu/data',
            'queue_size': 10,
            'qos': 1,
            'rtabmap_args': rtabmap_args,
            'database_path': database_path,
            'localization': localization,
            'map_frame_id': 'map',
            'wait_for_transform': 5.0,
            'RGBD/CreateOccupancyGrid': 'true',
            'Grid/Sensor': 'true',
            'rtabmapviz' : 'true',
            'map_always_update': True,
            'map_empty_ray_tracing': True,
        }],

        remappings=[
                ('left/image_rect', '/zed/zed_node/left/image_rect_color'),
                ('left/camera_info', '/zed/zed_node/left/camera_info'),
                ('right/image_rect', '/zed/zed_node/right/image_rect_color'),
                ('right/camera_info', '/zed/zed_node/right/camera_info'),
            ]
    ),


    Node(
        package='rtabmap_odom', executable='stereo_odometry', name='stereo_odometry', output='screen',
        parameters=[{
            "frame_id": 'base_footprint',
            "odom_frame_id": 'odom',
            "publish_tf": True,
            "wait_for_transform": 5.0,
            "wait_imu_to_init": False,
            "sync_queue_size": True,
            "qos": 1,
            "subscribe_rgbd": False,
            'rtabmapviz' : 'true',
        }],

        remappings=[
                ('left/image_rect', '/zed/zed_node/left/image_rect_color'),
                ('left/camera_info', '/zed/zed_node/left/camera_info'),
                ('right/image_rect', '/zed/zed_node/right/image_rect_color'),
                ('right/camera_info', '/zed/zed_node/right/camera_info'),
                ('imu', '/zed/zed_node/imu/data'),
            ]
        ),    
])
@matlabbe
Copy link
Member

matlabbe commented Dec 2, 2024

Something looks off in the image you shared, the stereo images don't look correctly stereo rectified as we can see vertical disparity. That would affect the quality of the point cloud a lot, and also would cause very bad odometry.

Beside that, the floor is indeed textureless, so no depth would be computed on it. If you can see only obstacles and want more empty cells in the map, you can enable ray tracing:

'Grid/3D': 'false',
'Grid/RayTracing': 'true',
'Grid/NormalsSegmentation': 'false',
'Grid/MaxGroundHeight': '0.1',

@InDroKalena
Copy link
Author

Thank you so much! I will keep playing around with parameters but these simple changes helped immediately.

image

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