rtabmap_ros icon indicating copy to clipboard operation
rtabmap_ros copied to clipboard

3D map drifting on NovaCarter with RTAB-Map

Open Shailesh-Pawar-12 opened this issue 7 months ago • 3 comments

I've set up RTAB-Map on the NovaCarter robot (ROS 2), but the 3D map is drifting noticeably — especially visible in the bottom-right corner of the screen in the attached screenshot. There are no errors in the console.

Attaching the launch file I'm using. Any idea what could be causing the drift?

Image Image

rtabmap launch file

from launch import LaunchDescription from launch.actions import DeclareLaunchArgument, SetEnvironmentVariable from launch.substitutions import LaunchConfiguration from launch.conditions import IfCondition, UnlessCondition from launch_ros.actions import Node

def generate_launch_description():

use_sim_time = LaunchConfiguration('use_sim_time')
localization = LaunchConfiguration('localization')
robot_ns = LaunchConfiguration('robot_ns')

rtabmap_parameters={
      'subscribe_rgbd':True,
      'subscribe_scan_cloud':True,
      'use_action_for_goal':True,
      'odom_sensor_sync': True,
      # RTAB-Map's parameters should be strings:
      'Mem/NotLinkedNodesKept':'false',
      'Grid/RangeMin':'1.0', # ignore laser scan points on the robot itself
      'Grid/NormalsSegmentation':'false', # Use passthrough filter to detect obstacles
      'Grid/MaxGroundHeight':'0.05', # All points above 5 cm are obstacles
      'Grid/MaxObstacleHeight':'1',  # All points over 1 meter are ignored
      'Grid/RayTracing':'true', # Fill empty space
      'Grid/3D':'false', # Use 2D occupancy
      'RGBD/OptimizeMaxError':'0.3', # There are a lot of repetitive patterns, be more strict in accepting loop closures
}

# Shared parameters between different nodes
shared_parameters={
      'frame_id':'base_link',
      'use_sim_time':use_sim_time,
      # RTAB-Map's parameters should be strings:
      'Reg/Strategy':'1',
      'Reg/Force3DoF':'true', # we are moving on a 2D flat floor
      'Mem/NotLinkedNodesKept':'false',
}

remappings=[
      ('/tf', 'tf'),
      ('/tf_static', 'tf_static'),
      ('odom', '/chassis/odom'),
      ('scan_cloud', '/front_3d_lidar/lidar_points'),
      ('rgb/image', '/front_stereo_camera/left/image_raw'),
      ('rgb/camera_info', '/front_stereo_camera/left/camera_info'),
      ('depth/image', '/front_stereo_camera/depth')]

return LaunchDescription([

    # Launch arguments
    DeclareLaunchArgument(
        'use_sim_time', default_value='false', choices=['true', 'false'],
        description='Use simulation (Gazebo) clock if true'),
    
    DeclareLaunchArgument(
        'localization', default_value='false', choices=['true', 'false'],
        description='Launch rtabmap in localization mode (a map should have been already created).'),

    # Nodes to launch
    Node(
        package='rtabmap_sync', executable='rgbd_sync', output='screen',
        parameters=[{'approx_sync':False, 'use_sim_time':use_sim_time}],
        remappings=remappings),

    # SLAM Mode:
    Node(
        condition=UnlessCondition(localization),
        package='rtabmap_slam', executable='rtabmap', output='screen',
        # namespace=robot_ns,
        parameters=[rtabmap_parameters, shared_parameters],
        remappings=remappings,
        arguments=['-d']),
        
    # Localization mode:
    Node(
        condition=IfCondition(localization),
        package='rtabmap_slam', executable='rtabmap', output='screen',
        # namespace=robot_ns,
        parameters=[rtabmap_parameters, shared_parameters,
          {'Mem/IncrementalMemory':'False',
           'Mem/InitWMWithAllNodes':'True'}],
        remappings=remappings),

    Node(
        package='rtabmap_viz', executable='rtabmap_viz', output='screen',
        # namespace=robot_ns,
        parameters=[rtabmap_parameters, shared_parameters],
        remappings=remappings),
])

Shailesh-Pawar-12 avatar May 08 '25 11:05 Shailesh-Pawar-12

The images should be rectified. There is an example here: https://github.com/introlab/rtabmap_ros/blob/ros2/rtabmap_demos/launch/isaac/isaac_sim_vslam_demo.launch.py

matlabbe avatar May 08 '25 17:05 matlabbe

@matlabbe Thank you for your reply!

I'm not using VLSAM for the Nova Carter, as mentioned in your example. Instead, I have a 3D LiDAR, an RGB-D camera, and an IMU. Could you please share a reference launch file or example configuration that uses these sensors with RTAB-Map?

Shailesh-Pawar-12 avatar May 09 '25 14:05 Shailesh-Pawar-12

I don't have example with 3D LiDAR on isaac simulator. Last time I tried it I was not satisfied with how they simulated a 3D LiDAR with 3 or 4 wide angle cameras not triggering at the same time. However, we have a Gazebo demo with similar sensors: https://github.com/introlab/rtabmap_ros/tree/ros2/rtabmap_demos#clearpath-husky-nav2-3d-lidar-and-rgb-d-slam, in particular that launch file husky_slam3d.launch.py that could be included in your setup.

matlabbe avatar May 12 '25 05:05 matlabbe