Skip to content

Implementing multi-TurtleBot navigation in a real-world environment #1123

@hyun0403

Description

@hyun0403

Operating System:

Ubuntu 22.04

ROS version :

Humble

Turtlebot3 Model:

Burger

Description

Hello,

I am trying to set up multi-robot navigation for several physical TurtleBot3s from a single remote PC, following the Load Multiple TurtleBot3s section of the TurtleBot3 E-Manual.

As a first step, I am attempting to get navigation working on a single robot with a namespace applied.

I launched the robot's bringup in a real-world environment with a namespace, as per the e-manual: $ ros2 launch turtlebot3_bringup robot.launch.py namespace:=tb3_1

I then modified the turtlebot3_navigation2 launch file to apply this namespace to the navigation stack as well.

Here is my modified navigation launch file:

#!/usr/bin/env python3
import os

from ament_index_python.packages import get_package_share_directory
from launch import LaunchDescription
from launch.actions import DeclareLaunchArgument, IncludeLaunchDescription
from launch.launch_description_sources import PythonLaunchDescriptionSource
from launch.substitutions import LaunchConfiguration
from launch_ros.actions import Node

TURTLEBOT3_MODEL = os.environ['TURTLEBOT3_MODEL']
ROS_DISTRO = os.environ.get('ROS_DISTRO')
def generate_launch_description():

    namespace = LaunchConfiguration('namespace', default='TB3_1')

    use_sim_time = LaunchConfiguration('use_sim_time', default='false')
    map_dir = LaunchConfiguration(
        'map',
        default=os.path.join(
            get_package_share_directory('turtlebot3_navigation2'),
            'map', 'map.yaml'))

    param_file_name =  'burger_tb3_1.yaml'
    param_dir = LaunchConfiguration(
        'params_file',
        default=os.path.join(
            get_package_share_directory('turtlebot3_navigation2'),
            'param',
            param_file_name))

    nav2_launch_file_dir = os.path.join(get_package_share_directory('nav2_bringup'), 'launch')

    rviz_config_file = LaunchConfiguration(
        'rviz_config_file',
        default=os.path.join(
            get_package_share_directory('turtlebot3_navigation2'),
            'rviz', 'nav2_ns_view.rviz')
    )

    return LaunchDescription([
        DeclareLaunchArgument('namespace', default_value=namespace, description='Robot namespace'),
        DeclareLaunchArgument('map', default_value=map_dir, description='Full path to map file to load'),
        DeclareLaunchArgument('params_file', default_value=param_dir, description='Full path to param file to load'),
        DeclareLaunchArgument('use_sim_time', default_value='false', description='Use simulation clock if true'),
        DeclareLaunchArgument('rviz_config_file', default_value=rviz_config_file, description='RViz config'),

        IncludeLaunchDescription(
            PythonLaunchDescriptionSource([nav2_launch_file_dir, '/bringup_launch.py']),
            launch_arguments={
                'namespace': namespace,
                'use_namespace': 'True',
                'map': map_dir,
                'use_sim_time': use_sim_time,
                'params_file': param_dir
            }.items(),
        ),

        IncludeLaunchDescription(
            PythonLaunchDescriptionSource(
                os.path.join(nav2_launch_file_dir, 'rviz_launch.py')),
            launch_arguments={
                'use_sim_time': use_sim_time,
                'namespace': namespace,
                'use_namespace': 'False',
                'rviz_config': rviz_config_file,
                'log_level': 'warn'
            }.items(),
        ),
    ])

In this launch file, I added 'namespace': namespace and 'use_namespace': 'True' to the bringup_launch.py inclusion.

I also tried adding 'namespace': namespace and 'use_namespace': 'True' to the rviz_launch.py inclusion. However, when use_namespace was True for RViz, no frames or other data would appear. Setting it to 'use_namespace': 'False' (as shown in the code above) makes the frames appear.

  • rviz_launch.pyuse_namespace’: 'True'
Image
  • rviz_launch.pyuse_namespace’: 'False'
Image

The Problem
With this setup (use_namespace: 'False' for RViz), the frames appear, but I am facing several critical problems:

Costmap Issue: The local and global costmaps are not subscribing to the scan topic.

AMCL Issue: Even after publishing an initial pose (to /TB3_1/initialpose with frame_id: 'TB3_1/map'), AMCL does not seem to initialize. The map -> odom transform is never published, breaking the TF tree.

Here is my rqt_graph. You can see that amcl, local_costmap, and global_costmap are not connected to the /scan topic (which is correctly namespaced to /TB3_1/scan).

  • rqt_graph
Image Image

My terminal log confirms the TF issue, showing Timed out waiting for transform from TB3_1/base_link to TB3_1/odom and AMCL Message Filter dropping message errors.

rviz2-2] [ERROR] [1760942859.961255804] [rviz2]: Vertex Program:rviz/glsl120/indexed_8bit_image.vert Fragment Program:rviz/glsl120/indexed_8bit_image.frag GLSL link result : 
[rviz2-2] active samplers with a different type refer to the same texture image unit
[component_container_isolated-1] [INFO] [1760942859.978919813] [TB3_1.lifecycle_manager_navigation]: Configuring waypoint_follower
[component_container_isolated-1] [INFO] [1760942859.979021415] [TB3_1.waypoint_follower]: Configuring
[component_container_isolated-1] [INFO] [1760942859.986462934] [TB3_1.waypoint_follower]: Created waypoint_task_executor : wait_at_waypoint of type nav2_waypoint_follower::WaitAtWaypoint
[component_container_isolated-1] [INFO] [1760942859.987226956] [TB3_1.lifecycle_manager_navigation]: Configuring velocity_smoother
[component_container_isolated-1] [INFO] [1760942859.987334038] [TB3_1.velocity_smoother]: Configuring velocity smoother
[component_container_isolated-1] [INFO] [1760942859.990065525] [TB3_1.lifecycle_manager_navigation]: Activating controller_server
[component_container_isolated-1] [INFO] [1760942859.990172578] [TB3_1.controller_server]: Activating
[component_container_isolated-1] [INFO] [1760942859.990201622] [TB3_1.local_costmap.local_costmap]: Activating
[component_container_isolated-1] [INFO] [1760942859.990215188] [TB3_1.local_costmap.local_costmap]: Checking transform
[component_container_isolated-1] [INFO] [1760942859.990235126] [TB3_1.local_costmap.local_costmap]: Timed out waiting for transform from TB3_1/base_link to TB3_1/odom to become available, tf error: Invalid frame ID "TB3_1/odom" passed to canTransform argument target_frame - frame does not exist
[component_container_isolated-1] [INFO] [1760942860.490291427] [TB3_1.local_costmap.local_costmap]: Timed out waiting for transform from TB3_1/base_link to TB3_1/odom to become available, tf error: Invalid frame ID "TB3_1/odom" passed to canTransform argument target_frame - frame does not exist
[component_container_isolated-1] [INFO] [1760942860.990324404] [TB3_1.local_costmap.local_costmap]: Timed out waiting for transform from TB3_1/base_link to TB3_1/odom to become available, tf error: Invalid frame ID "TB3_1/odom" passed to canTransform argument target_frame - frame does not exist
...
[component_container_isolated-1] [INFO] [1760942875.203844537] [TB3_1.amcl]: Message Filter dropping message: frame 'TB3_1/base_scan' at time 1760942874.274 for reason 'the timestamp on the message is earlier than all the data in the transform cache'
[component_container_isolated-1] [INFO] [1760942875.302896254] [TB3_1.amcl]: Message Filter dropping message: frame 'TB3_1/base_scan' at time 1760942874.374 for reason 'the timestamp on the message is earlier than all the data in the transform cache'
[component_container_isolated-1] [INFO] [1760942875.400622078] [TB3_1.amcl]: Message Filter dropping message: frame 'TB3_1/base_scan' at time 1760942874.474 for reason 'discarding message because the queue is full'
[component_container_isolated-1] [INFO] [1760942875.490295830] [TB3_1.local_costmap.local_costmap]: Timed out waiting for transform from TB3_1/base_link to TB3_1/odom to become available, tf error: Invalid frame ID "TB3_1/odom" passed to canTransform argument target_frame - frame does not exist
[component_container_isolated-1] [INFO] [1760942875.506691594] [TB3_1.amcl]: Message Filter dropping message: frame 'TB3_1/base_scan' at time 1760942874.574 for reason 'discarding message because the queue is full'
[component_container_isolated-1] [INFO] [1760942875.610002793] [TB3_1.amcl]: Message Filter dropping message: frame 'TB3_1/base_scan' at time 1760942874.684 for reason 'the timestamp on the message is earlier than all the data in the transform cache'
[component_container_isolated-1] [INFO] [1760942875.706476423] [TB3_1.amcl]: Message Filter dropping message: frame 'TB3_1/base_scan' at time 1760942874.784 for reason 'the timestamp on the message is earlier than all the data in the transform cache'

My Attempted Solution (Modifying Parameters)
I suspected the problem was in the Nav2 parameters .yaml file (burger_tb3_1.yaml). I manually prepended the namespace TB3_1/ to all frame_id parameters in amcl, bt_navigator, local_costmap, global_costmap, and map_server.

However, I noticed that amcl still has scan_topic: scan and the costmaps have topic: /scan. This might be the problem, but I'm not sure what they should be.

Here is my full burger_tb3_1.yaml file:

amcl:
  ros__parameters:
    use_sim_time: False
    alpha1: 0.2
    alpha2: 0.2
    alpha3: 0.2
    alpha4: 0.2
    alpha5: 0.2
    base_frame_id: "TB3_1/base_footprint"
    beam_skip_distance: 0.5
    beam_skip_error_threshold: 0.9
    beam_skip_threshold: 0.3
    do_beamskip: false
    global_frame_id: "TB3_1/map"
    lambda_short: 0.1
    laser_likelihood_max_dist: 2.0
    laser_max_range: 100.0
    laser_min_range: -1.0
    laser_model_type: "likelihood_field"
    max_beams: 60
    max_particles: 2000
    min_particles: 500
    odom_frame_id: "TB3_1/odom"
    pf_err: 0.05
    pf_z: 0.99
    recovery_alpha_fast: 0.0
    recovery_alpha_slow: 0.0
    resample_interval: 1
    robot_model_type: "nav2_amcl::DifferentialMotionModel"
    save_pose_rate: 0.5
    sigma_hit: 0.2
    tf_broadcast: true
    transform_tolerance: 1.0
    update_min_a: 0.2
    update_min_d: 0.25
    z_hit: 0.5
    z_max: 0.05
    z_rand: 0.5
    z_short: 0.05
    scan_topic: scan

amcl_map_client:
  ros__parameters:
    use_sim_time: False

amcl_rclcpp_node:
  ros__parameters:
    use_sim_time: False

bt_navigator:
  ros__parameters:
    use_sim_time: False
    global_frame: TB3_1/map
    robot_base_frame: TB3_1/base_link
    odom_topic: /TB3_1/odom
    default_bt_xml_filename: "navigate_w_replanning_and_recovery.xml"
    bt_loop_duration: 10
    default_server_timeout: 20
    enable_groot_monitoring: True
    groot_zmq_publisher_port: 1666
    groot_zmq_server_port: 1667
    plugin_lib_names:
    - nav2_compute_path_to_pose_action_bt_node
    - nav2_compute_path_through_poses_action_bt_node
    - nav2_follow_path_action_bt_node
    - nav2_back_up_action_bt_node
    - nav2_spin_action_bt_node
    - nav2_wait_action_bt_node
    - nav2_clear_costmap_service_bt_node
    - nav2_is_stuck_condition_bt_node
    - nav2_goal_reached_condition_bt_node
    - nav2_goal_updated_condition_bt_node
    - nav2_initial_pose_received_condition_bt_node
    - nav2_reinitialize_global_localization_service_bt_node
    - nav2_rate_controller_bt_node
    - nav2_distance_controller_bt_node
    - nav2_speed_controller_bt_node
    - nav2_truncate_path_action_bt_node
    - nav2_goal_updater_node_bt_node
    - nav2_recovery_node_bt_node
    - nav2_pipeline_sequence_bt_node
    - nav2_round_robin_node_bt_node
    - nav2_transform_available_condition_bt_node
    - nav2_time_expired_condition_bt_node
    - nav2_distance_traveled_condition_bt_node
    - nav2_single_trigger_bt_node
    - nav2_is_battery_low_condition_bt_node
    - nav2_navigate_through_poses_action_bt_node
    - nav2_navigate_to_pose_action_bt_node
    - nav2_remove_passed_goals_action_bt_node
    - nav2_planner_selector_bt_node
    - nav2_controller_selector_bt_node
    - nav2_goal_checker_selector_bt_node

bt_navigator_rclcpp_node:
  ros__parameters:
    use_sim_time: False

controller_server:
  ros__parameters:
    use_sim_time: False
    controller_frequency: 10.0
    min_x_velocity_threshold: 0.001
    min_y_velocity_threshold: 0.5
    min_theta_velocity_threshold: 0.001
    failure_tolerance: 0.3
    progress_checker_plugin: "progress_checker"
    goal_checker_plugins: ["general_goal_checker"] 
    controller_plugins: ["FollowPath"]

    # Progress checker parameters
    progress_checker:
      plugin: "nav2_controller::SimpleProgressChecker"
      required_movement_radius: 0.5
      movement_time_allowance: 10.0
    
    general_goal_checker:
      stateful: True
      plugin: "nav2_controller::SimpleGoalChecker"
      xy_goal_tolerance: 0.25
      yaw_goal_tolerance: 0.25

    # DWB parameters
    FollowPath:
      plugin: "dwb_core::DWBLocalPlanner"
      debug_trajectory_details: True
      min_vel_x: 0.0
      min_vel_y: 0.0
      max_vel_x: 0.22
      max_vel_y: 0.0
      max_vel_theta: 1.0
      min_speed_xy: 0.0
      max_speed_xy: 0.22
      min_speed_theta: 0.0
      # Add high threshold velocity for turtlebot 3 issue.
      # https://github.com/ROBOTIS-GIT/turtlebot3_simulations/issues/75
      acc_lim_x: 2.5
      acc_lim_y: 0.0
      acc_lim_theta: 3.2
      decel_lim_x: -2.5
      decel_lim_y: 0.0
      decel_lim_theta: -3.2
      vx_samples: 20
      vy_samples: 0
      vtheta_samples: 40
      sim_time: 1.5
      linear_granularity: 0.05
      angular_granularity: 0.025
      transform_tolerance: 0.2
      xy_goal_tolerance: 0.05
      trans_stopped_velocity: 0.25
      short_circuit_trajectory_evaluation: True
      stateful: True
      critics: ["RotateToGoal", "Oscillation", "BaseObstacle", "GoalAlign", "PathAlign", "PathDist", "GoalDist"]
      BaseObstacle.scale: 0.02
      PathAlign.scale: 32.0
      PathAlign.forward_point_distance: 0.1
      GoalAlign.scale: 24.0
      GoalAlign.forward_point_distance: 0.1
      PathDist.scale: 32.0
      GoalDist.scale: 24.0
      RotateToGoal.scale: 32.0
      RotateToGoal.slowing_factor: 5.0
      RotateToGoal.lookahead_time: -1.0
      
controller_server_rclcpp_node:
  ros__parameters:
    use_sim_time: False

local_costmap:
  local_costmap:
    ros__parameters:
      update_frequency: 5.0
      publish_frequency: 2.0
      global_frame: TB3_1/odom
      robot_base_frame: TB3_1/base_link
      use_sim_time: False
      rolling_window: true
      width: 3
      height: 3
      resolution: 0.05
      robot_radius: 0.1
      plugins: ["obstacle_layer", "voxel_layer", "inflation_layer"]
      inflation_layer:
        plugin: "nav2_costmap_2d::InflationLayer"
        inflation_radius: 1.0
        cost_scaling_factor: 3.0
      obstacle_layer:
        plugin: "nav2_costmap_2d::ObstacleLayer"
        enabled: True
        observation_sources: scan
        scan:
          topic: /scan
          max_obstacle_height: 2.0
          clearing: True
          marking: True
          data_type: "LaserScan"
      voxel_layer:
        plugin: "nav2_costmap_2d::VoxelLayer"
        enabled: True
        publish_voxel_map: True
        origin_z: 0.0
        z_resolution: 0.05
        z_voxels: 16
        max_obstacle_height: 2.0
        mark_threshold: 0
        observation_sources: scan
        scan:
          topic: /scan
          max_obstacle_height: 2.0
          clearing: True
          marking: True
          data_type: "LaserScan"
          raytrace_max_range: 3.0
          raytrace_min_range: 0.0
          obstacle_max_range: 2.5
          obstacle_min_range: 0.0
      static_layer:
        map_subscribe_transient_local: True
      always_send_full_costmap: True
  local_costmap_client:
    ros__parameters:
      use_sim_time: False
  local_costmap_rclcpp_node:
    ros__parameters:
      use_sim_time: False

global_costmap:
  global_costmap:
    ros__parameters:
      update_frequency: 1.0
      publish_frequency: 1.0
      global_frame: TB3_1/map
      robot_base_frame: TB3_1/base_link
      use_sim_time: False
      robot_radius: 0.1
      resolution: 0.05
      track_unknown_space: true
      plugins: ["static_layer", "obstacle_layer", "voxel_layer", "inflation_layer"]
      obstacle_layer:
        plugin: "nav2_costmap_2d::ObstacleLayer"
        enabled: True
        observation_sources: scan
        scan:
          topic: /scan
          max_obstacle_height: 2.0
          clearing: True
          marking: True
          data_type: "LaserScan"
          raytrace_max_range: 3.0
          raytrace_min_range: 0.0
          obstacle_max_range: 2.5
          obstacle_min_range: 0.0
      voxel_layer:
        plugin: "nav2_costmap_2d::VoxelLayer"
        enabled: True
        publish_voxel_map: True
        origin_z: 0.0
        z_resolution: 0.05
        z_voxels: 16
        max_obstacle_height: 2.0
        mark_threshold: 0
        observation_sources: scan
        scan:
          topic: /scan
          max_obstacle_height: 2.0
          clearing: True
          marking: True
          data_type: "LaserScan"
          raytrace_max_range: 3.0
          raytrace_min_range: 0.0
          obstacle_max_range: 2.5
          obstacle_min_range: 0.0
      static_layer:
        plugin: "nav2_costmap_2d::StaticLayer"
        map_subscribe_transient_local: True
      inflation_layer:
        plugin: "nav2_costmap_2d::InflationLayer"
        cost_scaling_factor: 3.0
        inflation_radius: 0.55
      always_send_full_costmap: True
  global_costmap_client:
    ros__parameters:
      use_sim_time: False
  global_costmap_rclcpp_node:
    ros__parameters:
      use_sim_time: False

map_server:
  ros__parameters:
    use_sim_time: False
    yaml_filename: "map.yaml"
    frame_id: "TB3_1/map"

map_saver:
  ros__parameters:
    use_sim_time: False
    save_map_timeout: 5.0
    free_thresh_default: 0.25
    occupied_thresh_default: 0.65
    map_subscribe_transient_local: True

planner_server:
  ros__parameters:
    expected_planner_frequency: 20.0
    use_sim_time: False
    planner_plugins: ["GridBased"]
    GridBased:
      plugin: "nav2_navfn_planner/NavfnPlanner"
      tolerance: 0.5
      use_astar: false
      allow_unknown: true

planner_server_rclcpp_node:
  ros__parameters:
    use_sim_time: False

recoveries_server:
  ros__parameters:
    costmap_topic: TB3_1/local_costmap/costmap_raw
    footprint_topic: TB3_1/local_costmap/published_footprint
    cycle_frequency: 10.0
    recovery_plugins: ["spin", "backup", "wait"]
    spin:
      plugin: "nav2_recoveries/Spin"
    backup:
      plugin: "nav2_recoveries/BackUp"
    wait:
      plugin: "nav2_recoveries/Wait"
    global_frame: TB3_1/odom
    robot_base_frame: TB3_1/base_link
    transform_timeout: 0.1
    use_sim_time: true
    simulate_ahead_time: 2.0
    max_rotational_vel: 1.0
    min_rotational_vel: 0.4
    rotational_acc_lim: 3.2

robot_state_publisher:
  ros__parameters:
    use_sim_time: False

waypoint_follower:
  ros__parameters:
    loop_rate: 2000
    stop_on_failure: false
    waypoint_task_executor_plugin: "wait_at_waypoint"   
    wait_at_waypoint:
      plugin: "nav2_waypoint_follower::WaitAtWaypoint"
      enabled: True
      waypoint_pause_duration: 200

I also modified my .rviz configuration file (nav2_ns_view.rviz) to use the namespaced frames, as shown below:

    - Alpha: 1
      Class: rviz_default_plugins/RobotModel
      Collision Enabled: false
      Description File: ""
      Description Source: Topic
      Description Topic:
        Depth: 5
        Durability Policy: Volatile
        History Policy: Keep Last
        Reliability Policy: Reliable
        Value: robot_description
      Enabled: false
      Links:
        All Links Enabled: true
        Expand Joint Details: false
        Expand Link Details: false
        Expand Tree: false
        Link Tree Style: ""
      Mass Properties:
        Inertia: false
        Mass: false
      Name: RobotModel
      TF Prefix: ""
      Update Interval: 0
      Value: false
      Visual Enabled: true
    - Class: rviz_default_plugins/TF
      Enabled: true
      Frame Timeout: 15
      Frames:
        All Enabled: false
        TB3_1/base_footprint:
          Value: true
        TB3_1/base_link:
          Value: true
        TB3_1/base_scan:
          Value: true
        TB3_1/camera_depth_frame:
          Value: true
        TB3_1/camera_depth_optical_frame:
          Value: true
        TB3_1/camera_link:
          Value: true
        TB3_1/camera_rgb_frame:
          Value: true
        TB3_1/camera_rgb_optical_frame:
          Value: true
        TB3_1/caster_back_left_link:
          Value: true
        TB3_1/caster_back_right_link:
          Value: true
        TB3_1/imu_link:
          Value: true
        TB3_1/map:
          Value: true
        TB3_1/odom:
          Value: true
        TB3_1/wheel_left_link:
          Value: true
        TB3_1/wheel_right_link:
          Value: true
      Marker Scale: 1
      Name: TF
      Show Arrows: true
      Show Axes: true
      Show Names: false
      Tree:
        TB3_1/map:
          TB3_1/odom:
            TB3_1/base_footprint:
              TB3_1/base_link:
                TB3_1/base_scan:
                  {}
                TB3_1/camera_link:
                  TB3_1/camera_depth_frame:
                    TB3_1/camera_depth_optical_frame:
                      {}
                  TB3_1/camera_rgb_frame:
                    TB3_1/camera_rgb_optical_frame:
                      {}
                TB3_1/caster_back_left_link:
                  {}
                TB3_1/caster_back_right_link:
                  {}
                TB3_1/imu_link:
                  {}
                TB3_1/wheel_left_link:
                  {}
                TB3_1/wheel_right_link:
                  {}
      Update Interval: 0
      Value: true

My Questions
I am trying to set up navigation for a single namespaced robot as the first step toward multi-robot navigation, but I am stuck.

  1. After applying a namespace, what frame_id should be used when publishing to the initialpose topic? (e.g., should I publish to /TB3_1/initialpose with frame_id: "TB3_1/map"?)

  2. If I fix issue 1, will this resolve the AMCL initialization failure (i.e., the missing map -> odom transform)? If AMCL still doesn't work correctly even after addressing this, what should I do next?"

  3. Why are the global and local costmaps not subscribing to the scan topic with my current configuration? My rqt_graph shows the topic is /TB3_1/scan, but my YAML file specifies topic: /scan for the costmap observation sources.

  4. What is the correct way to modify the .rviz configuration file and the Nav2 parameters .yaml file when applying a namespace to the entire bringup? Do I need to manually prefix every frame, or is there a better way?

Thank you for your help.

My modified code is attached below.
turtlebot3_navigation2.zip

Steps to reproduce issue

.

What Have You Tried?

Relevant logs / Terminal output

Screenshots or Diagrams

No response

Additional Information (Optional)

No response

Metadata

Metadata

Assignees

No one assigned

    Labels

    help wantedExtra attention is needed

    Type

    No type

    Projects

    Status

    🌱 Todo

    Milestone

    No milestone

    Relationships

    None yet

    Development

    No branches or pull requests

    Issue actions