[Unitree GO2] bt_navigator send_goal failed and TF issues during navigation

I’m working on Unitree Go2 using ROS 2 Foxy with the Nav2 navigation stack for autonomous multi-goal navigation.

The robot successfully navigates to the first 2D goal, but when I send a second or subsequent goal, several issues arise. Sometimes the robot fails just before reaching the goal, and in many cases, I need to restart map_navi.launch.py to regain navigation functionality.

Additional critical observation:

  • After the error occurs, the TF tree stops receiving updates.
  • As a result, the URDF visualization in RViz turns completely white, indicating the robot model is no longer receiving pose or transform updates.

This makes multi-goal autonomous navigation completely unreliable.
This has become a critical problem for executing sequential navigation tasks. I’ve tried multiple fixes but the issue persists

Detailed Error Logs:

Navigation failures during or after first goal:

[bt_navigator-7] [ERROR] [1760002653.479168237] [bt_navigator]: Action server failed while executing action callback: "send_goal failed"
[bt_navigator-7] [WARN] [1760002653.479294512] [bt_navigator]: [navigate_to_pose] [ActionServer] Aborting handle.

[bt_navigator-7] [ERROR] [1760002695.737271274] [bt_navigator]: Action server failed while executing action callback: "send_goal failed"
[bt_navigator-7] [WARN] [1760002695.737376396] [bt_navigator]: [navigate_to_pose] [ActionServer] Aborting handle.

[controller_server-4] [WARN] Control loop missed its desired rate of 10.0000Hz
[controller_server-4] [WARN] Control loop missed its desired rate of 10.0000Hz
[controller_server-4] [WARN] Control loop missed its desired rate of 10.0000Hz
[controller_server-4] [ERROR] Failed to make progress
[controller_server-4] [WARN] [follow_path] [ActionServer] Aborting handle.

[amcl-2] [INFO] Message Filter dropping message: frame 'lidar_link' at time ... for reason 'Unknown'
[amcl-2] [WARN] Failed to transform initial pose in time (Lookup would require extrapolation into the future)

Observations:

  • The first goal completes successfully.
  • Errors typically occur when the robot reaches or is near the second goal.
  • Control loop warnings indicate the controller_server cannot maintain its 10 Hz rate.
  • AMCL frequently drops messages or fails to transform the robot pose.

System Setup

  • ROS 2 Distribution: Foxy
  • Robot: Unitree Go2
  • Navigation Stack: Nav2 with DWBLocalPlanner
  • Controller Frequency: 10 Hz
  • Local Costmap: 6 x 6 m, resolution 0.05 m, update_frequency 2 Hz, publish_frequency 1 Hz
  • Global Costmap: 50 x 50 m, resolution 0.05 m, update_frequency 0.5 Hz, publish_frequency 0.5 Hz
  • Scan Topic: /go2_unit_38798/scan
  • Map Topic: /go2_unit_38798/map
  • Frames: map → odom → base_link → lidar_link
  • AMCL Parameters: max_particles=1000, min_particles=200, update_min_a=0.05, update_min_d=0.05, do_beamskip=false, laser_likelihood_max_dist=0.5

What I’ve Tried

  1. TF Verification
  • Checked the TF tree (map → odom → base_link → lidar_link) with tf2_tools view_frames.py.
  • Verified odom and base_link transforms are being published continuously.
  1. AMCL Tuning Attempts
  • Adjusted update_min_a and update_min_d to reduce excessive updates.
  • Monitored AMCL pose output; observed that it sometimes jumps to invalid positions after first goal.
  1. Controller / Planner Adjustments
  • Experimented with increasing controller frequency.
  • Modified sim_time, acceleration limits, and goal tolerances.
  • Verified DWBLocalPlanner configuration for velocity, acceleration, and trajectory evaluation.
  1. Costmap Management
  • Cleared local and global costmaps before sending new goals.
  • Observed local costmap updates occasionally lagging, possibly contributing to missed control loops.
  1. CPU / System Checks
  • Monitored CPU usage; observed spikes during AMCL updates and local costmap publishing.
  1. Recovery / Restart
  • After first goal fails, navigation only resumes after restarting map_navi.launch.py.

Also this is my nav2_map.yaml,

amcl:
  ros__parameters:
    use_sim_time: False
    alpha1: 0.1 #0.2
    alpha2: 0.2
    alpha3: 0.15 #0.2
    alpha4: 0.25 #0.2
    alpha5: 0.3 #0.2
    base_frame_id: "base_link"
    beam_skip_distance: 0.5
    beam_skip_error_threshold: 0.9
    beam_skip_threshold: 0.3
    do_beamskip: false
    global_frame_id: "map"
    lambda_short: 0.1
    laser_likelihood_max_dist: 0.5 #2.0
    laser_max_range: 100.0
    laser_min_range: -1.0
    laser_model_type: "likelihood_field"
    max_beams: 120 #60
    max_particles: 1000 #2000
    min_particles: 200 #500
    odom_frame_id: "odom"
    pf_err: 0.01 #0.05
    pf_z: 0.99
    recovery_alpha_fast: 0.1 #0.0
    recovery_alpha_slow: 0.001 #0.0
    resample_interval: 1
    robot_model_type: "omnidirectional"
    save_pose_rate: 0.5
    sigma_hit: 0.1 #0.2
    tf_broadcast: true
    transform_tolerance: 0.2 #1.0
    update_min_a: 0.05 #0.2
    update_min_d: 0.05 #0.25
    z_hit: 0.9 #0.5
    z_max: 0.03 #0.05
    z_rand: 0.05 #0.5
    z_short: 0.02 #0.05
    scan_topic: /go2_unit_38798/scan #scan
    set_initial_pose: true
    initial_pose:
      x: 0.0
      y: 0.0
      z: 0.0
      yaw: 0.0  # radians, calculated from orientation z/w

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: map
    robot_base_frame: base_link
    odom_topic: /go2_unit_38798/odometry/filtered
    default_bt_xml_filename: "navigate_w_replanning_and_recovery.xml"
    plugin_lib_names:
    - nav2_compute_path_to_pose_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_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

bt_navigator_rclcpp_node:
  ros__parameters:
    use_sim_time: False

controller_server:
  ros__parameters:
    use_sim_time: False
    controller_frequency: 20.0
    min_x_velocity_threshold: 0.001
    min_y_velocity_threshold: 0.001
    min_theta_velocity_threshold: 0.001
    controller_plugins: ["FollowPath"]

    # 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.3 #0.22
      max_vel_y: 0.3 #0.22
      max_vel_theta: 0.8 #0.5
      min_speed_xy: 0.0 #0.12
      max_speed_xy: 0.3 #0.12
      min_speed_theta: 0.0
      acc_lim_x: 2.5
      acc_lim_y: 2.5 #1.0
      acc_lim_theta: 3.2 #1.0
      decel_lim_x: -2.5
      decel_lim_y: -2.5
      decel_lim_theta: -3.2
      vx_samples: 20
      vy_samples: 5
      vtheta_samples: 20
      sim_time: 1.5 #10.0
      linear_granularity: 0.05
      angular_granularity: 0.025
      transform_tolerance: 0.2
      xy_goal_tolerance: 0.25
      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: 10.0 #5.0
      publish_frequency: 5.0 #2.0
      global_frame: odom
      robot_base_frame: base_link
      use_sim_time: False
      rolling_window: true
      width: 6
      height: 6
      resolution: 0.05
      footprint: '[[-0.4, -0.2], [-0.4, 0.2], [0.4, 0.2], [0.4, -0.2]]'
      footprint_padding: 0.3
      plugins: ["obstacle_layer", "inflation_layer"]
      inflation_layer:
        plugin: "nav2_costmap_2d::InflationLayer"
        cost_scaling_factor: 3.0
        inflation_radius: 0.4 #0.7
      obstacle_layer:
        plugin: "nav2_costmap_2d::ObstacleLayer"
        enabled: True
        observation_sources: scan
        scan:
          topic: /go2_unit_38798/scan #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: pointcloud
      #   pointcloud:
      #     topic: /utlidar/cloud_unused
      #     max_obstacle_height: 2.0
      #     clearing: True
      #     marking: True
      #     data_type: "PointCloud2"
      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: map
      robot_base_frame: base_link
      use_sim_time: False
      height: 50 
      width: 50
      origin_x: -50.0
      origin_y: -50.0
      footprint: '[[-0.4, -0.2], [-0.4, 0.2], [0.4, 0.2], [0.4, -0.2]]'
      resolution: 0.05
      plugins: ["static_layer", "obstacle_layer", "inflation_layer"]
      obstacle_layer:
        plugin: "nav2_costmap_2d::ObstacleLayer"
        enabled: True
        observation_sources: scan
        scan:
          topic: /go2_unit_38798/scan #scan
          max_obstacle_height: 2.0
          clearing: True
          marking: True
          data_type: "LaserScan"
      static_layer:
        plugin: "nav2_costmap_2d::StaticLayer"
        map_subscribe_transient_local: True
        enabled: true
        subscribe_to_updates: true
        transform_tolerance: 0.5 #0.1
      inflation_layer:
        plugin: "nav2_costmap_2d::InflationLayer"
        cost_scaling_factor: 3.0
        inflation_radius: 0.5 #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:
    frame_id: map
    topic_name: map
    use_sim_time: False
    yaml_filename: "/home/unitree/qre_ws/src/mybotshop/go2_navigation/maps/custom_map.yaml"

map_saver:
  ros__parameters:
    use_sim_time: False
    save_map_timeout: 5000
    free_thresh_default: 0.25
    occupied_thresh_default: 0.65

planner_server:
  ros__parameters:
    expected_planner_frequency: 20.0
    use_sim_time: False
    transform_tolerance: 1.0  # ADD THIS - allows 1 second tolerance
    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: local_costmap/costmap_raw
    footprint_topic: 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: odom
    robot_base_frame: base_link
    transform_timeout: 1.0
    use_sim_time: False
    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


Questions / Support Needed

  1. Why does bt_navigator send_goal failed occur after the first goal?
  2. Could the TF / AMCL errors be causing the controller_server to miss its control loop?
  3. How should AMCL, DWB, and costmap parameters be tuned for multi-goal navigation on Unitree Go2?
  4. Are there best practices for ensuring stable AMCL transforms and TF timing in ROS 2 Foxy with high-frequency LiDAR?

Any help, parameter suggestions, or debugging guidance would be greatly appreciated.

Thanks in advance!
Minindu Pasan

Does the first goal succeed. In the nav2 launch it should mention that goal reached successfully. It seems the odom topic is not being successfully reached by the controller server as it mentions that

Failed to make progress

It might be but the issue is more towards the controller_server.

This always depends on the map layout and how close you need to go to obstacles e.g. going through a door etc.

With Foxy im not so sure but you have basically put it such that it drops all points and keeps buffer of only the latest ones.

I would recommend switching out the controller and testing. Below I will give a nav2_param file, a and a behavior tree which you can use to switch out and try. You have to modify the parameters according to the go2 as well.

Behavior tree:

<root main_tree_to_execute="MainTree">
  <BehaviorTree ID="MainTree">

    <!-- Try the short pipeline; on failure, run RecoveryActions, then retry (up to N times) -->
    <RecoveryNode name="NavigateWithRecovery" number_of_retries="6">
      
      <!-- SHORT PIPELINE (unchanged behavior, just explicit ids) -->
      <PipelineSequence name="NavigateShort">
        <DistanceController distance="1.0">
          <ComputePathToPose goal="{goal}" path="{path}" planner_id="GridBased"/>
        </DistanceController>
        <FollowPath path="{path}" controller_id="FollowPath"/>
      </PipelineSequence>

      <!-- RECOVERY: clear local & global costmaps, then wait -->
      <SequenceStar name="RecoveryActions">
        <ClearEntireCostmap name="ClearLocalCostmap"
                            service_name="local_costmap/clear_entirely_local_costmap"/>
        <ClearEntireCostmap name="ClearGlobalCostmap"
                            service_name="global_costmap/clear_entirely_global_costmap"/>
        <Wait wait_duration="5"/>
      </SequenceStar>

    </RecoveryNode>

  </BehaviorTree>
</root>

Nav2 Params:

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: "base_link"
    beam_skip_distance: 0.5
    beam_skip_error_threshold: 0.9
    beam_skip_threshold: 0.3
    do_beamskip: false
    global_frame_id: "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: "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: "omnidirectional"
    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
    set_initial_pose: true
    initial_pose:
      x: -5.0
      y: -5.0
      z: 0.0
      yaw: 0.0   

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: map
    robot_base_frame: base_link
    odom_topic: /g1_unit_5849/odom
    default_bt_xml_filename: "/opt/mybotshop/src/mybotshop/g1_navigation/behavior_trees/navigate_w_replanning_and_recovery.xml"
    plugin_lib_names:
    - nav2_compute_path_to_pose_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_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

bt_navigator_rclcpp_node:
  ros__parameters:
    use_sim_time: False

controller_server:
  ros__parameters:
    use_sim_time: False
    controller_frequency: 20.0

    # thresholds small but non-zero
    min_x_velocity_threshold: 0.001
    min_y_velocity_threshold: 0.1    
    min_theta_velocity_threshold: 0.001

    failure_tolerance: 0.3
    progress_checker_plugin: "progress_checker"
    goal_checker_plugins: ["general_goal_checker"]
    controller_plugins: ["FollowPath"]
    odom_topic: /g1_unit_5849/odom

    # Progress checker (Foxy)
    progress_checker:
      plugin: "nav2_controller::SimpleProgressChecker"
      required_movement_radius: 0.3
      movement_time_allowance: 12.0

    # Goal checker (Foxy)
    general_goal_checker:
      stateful: True
      plugin: "nav2_controller::SimpleGoalChecker"
      xy_goal_tolerance: 0.25
      yaw_goal_tolerance: 0.2

    # ----------------- Regulated Pure Pursuit (RPP)
    FollowPath:
      plugin: "nav2_regulated_pure_pursuit_controller::RegulatedPurePursuitController"

      # Core kinematics (start conservative, tune upward)
      desired_linear_vel: 0.5
      min_approach_linear_velocity: 0.05
      max_angular_accel: 6.2
      max_linear_accel: 4.2
      use_rotate_to_heading: true
      rotate_to_heading_min_angle: 0.785
      rotate_to_heading_angular_vel: 0.2

      # Lookahead
      lookahead_dist: 0.4
      min_lookahead_dist: 0.1
      max_lookahead_dist: 1.2
      lookahead_time: 1.5
      use_velocity_scaled_lookahead_dist: false
      use_fixed_curvature_lookahead: false
      curvature_lookahead_dist: 0.6

      # Regulation / safety
      use_collision_detection: true
      max_allowed_time_to_collision: 1.5
      use_regulated_linear_velocity_scaling: true
      use_cost_regulated_linear_velocity_scaling: true
      regulated_linear_scaling_min_radius: 0.85
      regulated_linear_scaling_min_speed: 0.25
      approach_velocity_scaling_dist: 0.3

      # Frames & numerics
      transform_tolerance: 0.1
      max_robot_pose_search_dist: 10.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: odom
      robot_base_frame: base_link
      use_sim_time: False
      rolling_window: true
      width: 6
      height: 6
      resolution: 0.05
      robot_radius: 0.35
      plugins: ["obstacle_layer", "inflation_layer"]
      inflation_layer:
        plugin: "nav2_costmap_2d::InflationLayer"
        cost_scaling_factor: 3.0
        inflation_radius: 0.4
      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: pointcloud
      #   pointcloud:
      #     topic: /utlidar/cloud_unused
      #     max_obstacle_height: 2.0
      #     clearing: True
      #     marking: True
      #     data_type: "PointCloud2"
      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: map
      robot_base_frame: base_link
      use_sim_time: False
      height: 50 
      width: 50
      origin_x: -50.0
      origin_y: -50.0
      robot_radius: 0.4
      resolution: 0.05
      plugins: ["static_layer", "inflation_layer"]      
      static_layer:
        plugin: "nav2_costmap_2d::StaticLayer"
        map_subscribe_transient_local: True
        enabled: true
        subscribe_to_updates: true
        transform_tolerance: 0.1
      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:
    frame_id: map   
    topic_name: map
    use_sim_time: False
    yaml_filename: "/home/administrator/projects/quadruped/qre_go2/src/g1_navigation/maps/cookies_are_good.yaml"

map_saver:
  ros__parameters:
    use_sim_time: False
    save_map_timeout: 5000
    free_thresh_default: 0.25
    occupied_thresh_default: 0.65

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: local_costmap/costmap_raw
    footprint_topic: local_costmap/published_footprint
    cycle_frequency: 10.0
    recovery_plugins: ["backup", "wait"]
    # spin:
    #   plugin: "nav2_recoveries/Spin"
    backup:
      plugin: "nav2_recoveries/BackUp"
    wait:
      plugin: "nav2_recoveries/Wait"
    global_frame: odom
    robot_base_frame: base_link
    transform_timeout: 1.0
    use_sim_time: False
    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