introlab / rtabmap_ros

RTAB-Map's ROS package.
http://wiki.ros.org/rtabmap_ros
BSD 3-Clause "New" or "Revised" License
922 stars 549 forks source link

Multiple rtabmap nodes using the same Mem/IncrementalMemory parameter. #1075

Closed Krzo99 closed 7 months ago

Krzo99 commented 7 months ago

I am using 2 robots to map an area. The idea is, to use localization mode, until reaching the edge of the map, and then turning on mapping mode, to save on database size. When I get to the edge of the map, I run: ros2 service call /leo1/set_mode_mapping std_srvs/srv/Empty {} I would think that this will only turn on the mapping mode on robot leo1, however, all avaliable robots switch to it. There is a bit of a different output, but the result is the same:

Leo1 output: [rtabmap-2] [INFO] [leo1.rtabmap]: rtabmap: Set mapping mode [rtabmap-2] [INFO] [leo1.rtabmap]: rtabmap: Mapping mode enabled! [rtabmap-2] [INFO] [leo1.rtabmap]: Setting RTAB-Map parameter "Mem/IncrementalMemory"="true" [rtabmap-2] [INFO] [leo1.rtabmap]: rtabmap: Updating parameters [rtabmap-2] [INFO] [leo1.rtabmap]: RTAB-Map rate detection = 1.000000 Hz

Leo2 output: [rtabmap-2] [INFO] [leo2.rtabmap]: Setting RTAB-Map parameter "Mem/IncrementalMemory"="true" [rtabmap-2] [INFO] [leo2.rtabmap]: rtabmap: Updating parameters [rtabmap-2] [INFO] [leo2.rtabmap]: RTAB-Map rate detection = 1.000000 Hz

The same thing happens when setting the parameter: ros2 param set /leo2/rtabmap Mem/IncrementalMemory "'true'"

The weird thing is, that both the robots start publishing and updating the map to rviz2 while moving, as if both of them are in maping mode (as seen from console output), but when calling ros2 param get /leo1/rtabmap Mem/IncrementalMemory for both robots, only the one that was explicitly set to mapping mode, returns true, and the other false. There seems to be a difference between ros2 param and actual state of rtabmap nodes.

The rtabmap launch file is launched two times, both in different bash instances, like so: ros2 launch pkg rtabmap.launch.py robot_ns:=leo1 The rtabmap launch file is:

def generate_launch_description():

    parameters = [{
        'frame_id': PathJoinSubstitution([LaunchConfiguration("robot_ns"), 'base_footprint']),
        'map_frame_id': 'map',
        'odom_frame_id': PathJoinSubstitution([LaunchConfiguration("robot_ns"), 'odom']),
        'subscribe_depth': True,
        'subscribe_odom_info': False,
        'approx_sync': True,
        'approx_sync_max_interval': 0.05,
        'wait_imu_to_init': True,
        'use_sim_time': True,
        "map_always_update": False,                                  # Keep sending the full map on cloud_map topic.
        "database_path": LaunchConfiguration("database_path"),       # Each robot has its own database.

        # RtabMap params
        'Rtabmap/DetectionRate': '1.0',              # Detection rate (Hz). RTAB-Map will filter input images to satisfy this rate.
        'Rtabmap/ImagesAlreadyRectified': 'false',   # By default RTAB-Map assumes that received images are rectified. If they are not, they can be rectified by RTAB-Map if this parameter is false.
        'Rtabmap/LoopThr': '0.11',                   # Loop closing threshold.

        'Odom/Strategy': '0',                        # [0=Frame-to-Map (F2M) 1=Frame-to-Frame (F2F) 2=Fovis 3=viso2 4=DVO-SLAM 5=ORB_SLAM2 6=OKVIS 7=LOAM 8=MSCKF_VIO 9=VINS-Fusion 10=OpenVINS 11=FLOAM 12=Open3D]
        'Odom/FilteringStrategy': '1' ,              # [0=No filtering 1=Kalman filtering 2=Particle filtering.]

        'Optimizer/Strategy': '2',                   # Graph optimization strategy: 0=TORO, 1=g2o, 2=GTSAM and 3=Ceres. Only 1 or 2 can be used.
        'Optimizer/Robust': 'true',                  # Robust graph optimization using Vertigo (only work for g2o and GTSAM optimization strategies). Not compatible with 'RGBD/OptimizeMaxError' if enabled.

        "RGBD/SavedLocalizationIgnored": 'false',    # Ignore saved localization if the loop closure is detected. This will force RTAB-Map to localize again in the current map.

        "Mem/IncrementalMemory": "false",            # true = mapping mode
        "Mem/ReduceGraph": "false",                  # Shuld make the database smaller.
        "Mem/SaveDepth16Format": "true",             # Save depth images in 16 bit format to save size.

        "Reg/Strategy": "0",                         # We use only visual odometry.

        }]

    remappings = [
        ('odom', 'odom_rgbd'),
        ('rgb/image', 'depth_camera/image_raw'),
        ('rgb/camera_info', 'depth_camera/camera_info'),
        ('depth/image', 'depth_camera/depth/image_raw')]

    return LaunchDescription([

        DeclareLaunchArgument(
            "database_path",
            default_value=["~/.ros/rtabmap_", LaunchConfiguration("robot_ns"), ".db"],
            description='Path to the database. A bit of a hack to pass it to database_path parameter.'
        ),

        DeclareLaunchArgument(
            name="robot_ns", 
            default_value="/", 
            description="Namespace of the robot"
        ),

        # Nodes to launch
        Node(
            package='rtabmap_odom', executable='rgbd_odometry', output='screen',
            namespace=LaunchConfiguration("robot_ns"),
            parameters=parameters,
            remappings=remappings
        ),

        Node(
            package='rtabmap_slam', executable='rtabmap', output='screen',
            namespace=LaunchConfiguration("robot_ns"),
            parameters=parameters,
            remappings=remappings,
        ),

Wouldn't it be more logical to be able to set only one robot into mapping mode, while the other still stays in localization mode?

matlabbe commented 7 months ago

Good catch! The problem was how SyncParametersClient is working, I wrongly assumed that this callback was only called for parameters set to that node, but the callback is called for parameters set to any nodes. If two nodes share same parameter name (even in different namespace), they would by default process them. In the commit above, I now check if the parameters are set in the expected namespace and node name. This should fix your issue.