ros-navigation / navigation2

ROS 2 Navigation Framework and System
https://nav2.org/
Other
2.47k stars 1.25k forks source link

AMCL is unable to correctly publish the map->odom coordinate transformation. #4584

Closed suixing108 closed 1 month ago

suixing108 commented 1 month ago

Hello, I am encountering some issues and it seems that AMCL is not working properly.I would greatly appreciate any assistance you can provide in resolving this @issue.

Environment Description:

bt_navigator: ros__parameters: global_frame: map robot_base_frame: base_link odom_topic: /odom bt_loop_duration: 10 default_server_timeout: 20 wait_for_service_timeout: 1000 action_server_result_timeout: 900.0 navigators: ["navigate_to_pose", "navigate_through_poses"] navigate_to_pose: plugin: "nav2_bt_navigator::NavigateToPoseNavigator" navigate_through_poses: plugin: "nav2_bt_navigator::NavigateThroughPosesNavigator"

'default_nav_through_poses_bt_xml' and 'default_nav_to_pose_bt_xml' are use defaults:

# nav2_bt_navigator/navigate_to_pose_w_replanning_and_recovery.xml
# nav2_bt_navigator/navigate_through_poses_w_replanning_and_recovery.xml
# They can be set here or via a RewrittenYaml remap from a parent launch file to Nav2.

# plugin_lib_names is used to add custom BT plugins to the executor (vector of strings).
# Built-in plugins are added automatically
# plugin_lib_names: []

error_code_names:
  - compute_path_error_code
  - follow_path_error_code

controller_server: ros__parameters: controller_frequency: 20.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_plugins: ["progress_checker"] goal_checker_plugins: ["general_goal_checker"] # "precise_goal_checker" controller_plugins: ["FollowPath"] use_realtime_priority: false

# Progress checker parameters
progress_checker:
  plugin: "nav2_controller::SimpleProgressChecker"
  required_movement_radius: 0.5
  movement_time_allowance: 10.0
# Goal checker parameters
#precise_goal_checker:
#  plugin: "nav2_controller::SimpleGoalChecker"
#  xy_goal_tolerance: 0.25
#  yaw_goal_tolerance: 0.25
#  stateful: True
general_goal_checker:
  stateful: True
  plugin: "nav2_controller::SimpleGoalChecker"
  xy_goal_tolerance: 0.25
  yaw_goal_tolerance: 0.25
FollowPath:
  plugin: "nav2_mppi_controller::MPPIController"
  time_steps: 56
  model_dt: 0.05
  batch_size: 2000
  ax_max: 3.0
  ax_min: -3.0
  ay_max: 3.0
  az_max: 3.5
  vx_std: 0.2
  vy_std: 0.2
  wz_std: 0.4
  vx_max: 0.5
  vx_min: -0.35
  vy_max: 0.5
  wz_max: 1.9
  iteration_count: 1
  prune_distance: 1.7
  transform_tolerance: 0.1
  temperature: 0.3
  gamma: 0.015
  motion_model: "DiffDrive"
  visualize: true
  regenerate_noises: true
  TrajectoryVisualizer:
    trajectory_step: 5
    time_step: 3
  AckermannConstraints:
    min_turning_r: 0.2
  critics: [
    "ConstraintCritic", "CostCritic", "GoalCritic",
    "GoalAngleCritic", "PathAlignCritic", "PathFollowCritic",
    "PathAngleCritic", "PreferForwardCritic"]
  ConstraintCritic:
    enabled: true
    cost_power: 1
    cost_weight: 4.0
  GoalCritic:
    enabled: true
    cost_power: 1
    cost_weight: 5.0
    threshold_to_consider: 1.4
  GoalAngleCritic:
    enabled: true
    cost_power: 1
    cost_weight: 3.0
    threshold_to_consider: 0.5
  PreferForwardCritic:
    enabled: true
    cost_power: 1
    cost_weight: 5.0
    threshold_to_consider: 0.5
  CostCritic:
    enabled: true
    cost_power: 1
    cost_weight: 3.81
    critical_cost: 300.0
    consider_footprint: true
    collision_cost: 1000000.0
    near_goal_distance: 1.0
    trajectory_point_step: 2
  PathAlignCritic:
    enabled: true
    cost_power: 1
    cost_weight: 14.0
    max_path_occupancy_ratio: 0.05
    trajectory_point_step: 4
    threshold_to_consider: 0.5
    offset_from_furthest: 20
    use_path_orientations: false
  PathFollowCritic:
    enabled: true
    cost_power: 1
    cost_weight: 5.0
    offset_from_furthest: 5
    threshold_to_consider: 1.4
  PathAngleCritic:
    enabled: true
    cost_power: 1
    cost_weight: 2.0
    offset_from_furthest: 4
    threshold_to_consider: 0.5
    max_angle_to_furthest: 1.0
    mode: 0
  # TwirlingCritic:
  #   enabled: true
  #   twirling_cost_power: 1
  #   twirling_cost_weight: 10.0

local_costmap: local_costmap: ros__parameters: update_frequency: 5.0 publish_frequency: 2.0 global_frame: odom robot_base_frame: base_link rolling_window: true width: 3 height: 3 resolution: 0.05 robot_radius: 0.22 plugins: ["voxel_layer", "inflation_layer"] inflation_layer: plugin: "nav2_costmap_2d::InflationLayer" cost_scaling_factor: 3.0 inflation_radius: 0.70 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 always_send_full_costmap: True

global_costmap: global_costmap: ros__parameters: update_frequency: 1.0 publish_frequency: 1.0 global_frame: map robot_base_frame: base_link robot_radius: 0.22 resolution: 0.05 track_unknown_space: true plugins: ["static_layer", "obstacle_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 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.25 always_send_full_costmap: True

The yaml_filename does not need to be specified since it going to be set by defaults in launch.

If you'd rather set it in the yaml, remove the default "map" value in the tb3_simulation_launch.py

file & provide full path to map below. If CLI map configuration or launch default is provided, that will be used.

map_server:

ros__parameters:

yaml_filename: ""

map_saver: ros__parameters: 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 planner_plugins: ["GridBased"] GridBased: plugin: "nav2_navfn_planner::NavfnPlanner" tolerance: 0.5 use_astar: false allow_unknown: true

smoother_server: ros__parameters: smoother_plugins: ["simple_smoother"] simple_smoother: plugin: "nav2_smoother::SimpleSmoother" tolerance: 1.0e-10 max_its: 1000 do_refinement: True

behavior_server: ros__parameters: local_costmap_topic: local_costmap/costmap_raw global_costmap_topic: global_costmap/costmap_raw local_footprint_topic: local_costmap/published_footprint global_footprint_topic: global_costmap/published_footprint cycle_frequency: 10.0 behavior_plugins: ["spin", "backup", "drive_on_heading", "assisted_teleop", "wait"] spin: plugin: "nav2_behaviors::Spin" backup: plugin: "nav2_behaviors::BackUp" drive_on_heading: plugin: "nav2_behaviors::DriveOnHeading" wait: plugin: "nav2_behaviors::Wait" assisted_teleop: plugin: "nav2_behaviors::AssistedTeleop" local_frame: odom global_frame: map robot_base_frame: base_link transform_tolerance: 0.1 simulate_ahead_time: 2.0 max_rotational_vel: 1.0 min_rotational_vel: 0.4 rotational_acc_lim: 3.2

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

velocity_smoother: ros__parameters: smoothing_frequency: 20.0 scale_velocities: False feedback: "OPEN_LOOP" max_velocity: [0.5, 0.0, 2.0] min_velocity: [-0.5, 0.0, -2.0] max_accel: [2.5, 0.0, 3.2] max_decel: [-2.5, 0.0, -3.2] odom_topic: "odom" odom_duration: 0.1 deadband_velocity: [0.0, 0.0, 0.0] velocity_timeout: 1.0

collision_monitor: ros__parameters: base_frame_id: "base_link" odom_frame_id: "odom" cmd_vel_in_topic: "cmd_vel_smoothed" cmd_vel_out_topic: "cmd_vel" state_topic: "collision_monitor_state" transform_tolerance: 0.2 source_timeout: 1.0 base_shift_correction: True stop_pub_timeout: 2.0

Polygons represent zone around the robot for "stop", "slowdown" and "limit" action types,

# and robot footprint for "approach" action type.
polygons: ["FootprintApproach"]
FootprintApproach:
  type: "polygon"
  action_type: "approach"
  footprint_topic: "/local_costmap/published_footprint"
  time_before_collision: 1.2
  simulation_time_step: 0.1
  min_points: 6
  visualize: False
  enabled: True
observation_sources: ["scan"]
scan:
  type: "scan"
  topic: "scan"
  min_height: 0.15
  max_height: 2.0
  enabled: True

docking_server: ros__parameters: controller_frequency: 50.0 initial_perception_timeout: 5.0 wait_charge_timeout: 5.0 dock_approach_timeout: 30.0 undock_linear_tolerance: 0.05 undock_angular_tolerance: 0.1 max_retries: 3 base_frame: "base_link" fixed_frame: "odom" dock_backwards: false dock_prestaging_tolerance: 0.5

# Types of docks
dock_plugins: ['simple_charging_dock']
simple_charging_dock:
  plugin: 'opennav_docking::SimpleChargingDock'
  docking_threshold: 0.05
  staging_x_offset: -0.7
  use_external_detection_pose: true
  use_battery_status: false # true
  use_stall_detection: false # true

  external_detection_timeout: 1.0
  external_detection_translation_x: -0.18
  external_detection_translation_y: 0.0
  external_detection_rotation_roll: -1.57
  external_detection_rotation_pitch: -1.57
  external_detection_rotation_yaw: 0.0
  filter_coef: 0.1

# Dock instances
# The following example illustrates configuring dock instances.
# docks: ['home_dock']  # Input your docks here
# home_dock:
#   type: 'simple_charging_dock'
#   frame: map
#   pose: [0.0, 0.0, 0.0]

controller:
  k_phi: 3.0
  k_delta: 2.0
  v_linear_min: 0.15
  v_linear_max: 0.15


![微信图片_20240801112451](https://github.com/user-attachments/assets/cdd87dea-ef5b-4fc2-922e-c23b8d731d2f)
![微信图片_20240801112507](https://github.com/user-attachments/assets/ac60a0a7-04e4-4073-b71f-cf1cfb573705)
![微信图片_20240801112512](https://github.com/user-attachments/assets/67f76319-2c21-4bb3-b8f3-c70824ecd325)
![微信图片_20240801112515](https://github.com/user-attachments/assets/97bd2e29-7180-4160-9b43-e8ebca6ac826)
![微信图片_20240801112519](https://github.com/user-attachments/assets/2bb06b2e-a239-47fc-9cf4-a1ad4aec671a)
![微信图片_20240801112522](https://github.com/user-attachments/assets/28d7570b-dac5-4f42-aea7-fef4f1e270df)

### Attempted Solutions:
1、Replaced AMCL with Gmapping for the map->odom transformation. Navigation works correctly without any errors, but the inputted prior map cannot be displayed.
2、Started the map_server first to independently manage the lifecycle of the prior map, but the error "cannot find map->odom" still occurs.
3、I tried publishing the static transformation relationship for map->odom using: `ros2 run tf2_ros static_transform_publisher 0 0 0 0 0 0 map odom`. In this case, navigation works correctly.
SteveMacenski commented 1 month ago

Is the scan actually on the scan topic? This seems like a classic: everything's setup but you didn't give it data yet. Or, you didn't set the robot's initial pose so AMCL isn't initialized yet. Have you set that? Your clipped logs make this difficult to analyze.

I'm pretty convinced that this works since I use it every day, there's just something AMCL's not being given - I think - that it needs to get going. That's either a map, initial pose, or scan.

https://github.com/ros-navigation/navigation2/blob/main/nav2_amcl/src/amcl_node.cpp#L1562 --> this means the subscription was created, not that it was received. You'd see this log: https://github.com/ros-navigation/navigation2/blob/main/nav2_amcl/src/amcl_node.cpp#L1419 if a map was received. Maybe your map topic is different or not set up using the correct QoS?

suixing108 commented 1 month ago

Thank you very much for your reply, it has been very inspiring. To more accurately identify the problem, I will provide more details and look forward to your further response.

Problem Description

Before I start the robot, my ROS graph and topic list are as follows: rosgraph

r@r:~$ ros2 topic list 
/cmd_vel
/diagnostics
/imu
/joint_states
/lslidar_driver_node/transition_event
/lslidar_order
/odom
/parameter_events
/robot_description
/rosout
/scan
/tf
/tf_static

Launch File and Configuration File

Here is my launch file. In fact, I have only specified the path to the configuration file. The static transform is for my testing purposes, and I have already commented it out.

import os
from ament_index_python.packages import get_package_share_directory
from launch import LaunchDescription
from launch.actions import IncludeLaunchDescription, RegisterEventHandler
from launch.launch_description_sources import PythonLaunchDescriptionSource
from launch.substitutions import LaunchConfiguration
from launch_ros.actions import Node
from launch.event_handlers import OnProcessExit

def generate_launch_description():
    # 1. 定位到包的地址
    robot_navigation2_dir = get_package_share_directory('robot_nav')
    nav2_bringup_dir = get_package_share_directory('nav2_bringup')

    # 2. 声明参数,获取配置文件路径
    use_sim_time = LaunchConfiguration('use_sim_time', default='false')
    map_yaml_path = LaunchConfiguration('map', default=os.path.join(robot_navigation2_dir, 'maps', 'map.yaml'))
    nav2_param_path = LaunchConfiguration('params_file', default=os.path.join(robot_navigation2_dir, 'param', 'robot_params.yaml'))

    # # 3. 添加静态变换
    # static_transform_publisher = Node(
    #     package='tf2_ros',
    #     executable='static_transform_publisher',
    #     name='static_transform_publisher',
    #     output='screen',
    #     arguments=[
    #         '0.0', '0.0', '0.0',  # translation
    #         '0.0', '0.0', '0.0', '1.0',  # quaternion (w, x, y, z)
    #         'map', 'odom',  # source_frame, target_frame
    #     ]
    # )

    # 4. 声明启动launch文件,传入:地图路径、是否使用仿真时间以及nav2参数文件
    nav2_bringup_launch = IncludeLaunchDescription(
        PythonLaunchDescriptionSource([nav2_bringup_dir, '/launch/bringup_launch.py']),
        launch_arguments={
            'map': map_yaml_path,
            'use_sim_time': use_sim_time,
            'params_file': nav2_param_path
        }.items(),
    )
    #
    # # 5. 创建事件处理程序,确保静态变换发布后再启动nav2_bringup
    # on_exit_handler = RegisterEventHandler(
    #     event_handler=OnProcessExit(
    #         target_action=static_transform_publisher,
    #         on_exit=[nav2_bringup_launch],
    #     )
    # )

    # 如果需要启动 RViz,可以取消注释以下代码
    # rviz_config_dir = os.path.join(nav2_bringup_dir, 'rviz', 'nav2_default_view.rviz')
    # rviz_node = Node(
    #     package='rviz2',
    #     executable='rviz2',
    #     name='rviz2',
    #     arguments=['-d', rviz_config_dir],
    #     parameters=[{'use_sim_time': use_sim_time}],
    #     output='screen'
    # )
    # return LaunchDescription([nav2_bringup_launch, rviz_node])
    return LaunchDescription([
        nav2_bringup_launch,
        # rviz_node
    ])

    # return LaunchDescription([
    #     static_transform_publisher,
    #     on_exit_handler,
    # ])

Here are my configuration parameters:

amcl:
  ros__parameters:
#    alpha1 至 alpha5:运动模型中的噪声参数,用于调整运动模型的随机性。
    alpha1: 0.2   # 与前向旋转速度成正比的噪声
    alpha2: 0.2   # 前向速度
    alpha3: 0.2   # 横向速度
    alpha4: 0.2
    alpha5: 0.2
    base_frame_id: "base_link"  # 底盘坐标系
#    base_frame_id: "odom"
    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"    # 激光传感器模型类型,likelihood_field表示使用似然场模型
    max_beams: 60   # 用于定位的激光束最大数量
    max_particles: 2000   # 粒子滤波器中的最大粒子数
    min_particles: 500    # 最小粒子数
    odom_frame_id: "odom"   # 里程坐标系的名称
    map_frame_id: "map"     # add by l
    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    # 是否广播坐标变换,参数False可以防止amcl发布全局坐标系和里程计坐标系之间的坐标变换
    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    # 激光雷达数据的主题名称
    map_topic: map    # add by l  用于订阅地图的话题名称

bt_navigator:
  ros__parameters:
    global_frame: map   # 全局坐标系
    robot_base_frame: base_link   # 底盘坐标系
    odom_topic: /odom   # 里程计数据坐标系
    bt_loop_duration: 10
    default_server_timeout: 20
    wait_for_service_timeout: 1000
    action_server_result_timeout: 900.0
    navigators: ["navigate_to_pose", "navigate_through_poses"]
    navigate_to_pose:
      plugin: "nav2_bt_navigator::NavigateToPoseNavigator"
    navigate_through_poses:
      plugin: "nav2_bt_navigator::NavigateThroughPosesNavigator"
    # 'default_nav_through_poses_bt_xml' and 'default_nav_to_pose_bt_xml' are use defaults:
    # nav2_bt_navigator/navigate_to_pose_w_replanning_and_recovery.xml
    # nav2_bt_navigator/navigate_through_poses_w_replanning_and_recovery.xml
    # They can be set here or via a RewrittenYaml remap from a parent launch file to Nav2.

    # plugin_lib_names is used to add custom BT plugins to the executor (vector of strings).
    # Built-in plugins are added automatically
    # plugin_lib_names: []

    error_code_names:
      - compute_path_error_code
      - follow_path_error_code

controller_server:
  ros__parameters:
    controller_frequency: 20.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_plugins: ["progress_checker"]
    goal_checker_plugins: ["general_goal_checker"] # "precise_goal_checker"
    controller_plugins: ["FollowPath"]
    use_realtime_priority: false

    # Progress checker parameters
    progress_checker:
      plugin: "nav2_controller::SimpleProgressChecker"
      required_movement_radius: 0.5
      movement_time_allowance: 10.0
    # Goal checker parameters
    #precise_goal_checker:
    #  plugin: "nav2_controller::SimpleGoalChecker"
    #  xy_goal_tolerance: 0.25
    #  yaw_goal_tolerance: 0.25
    #  stateful: True
    general_goal_checker:
      stateful: True
      plugin: "nav2_controller::SimpleGoalChecker"
      xy_goal_tolerance: 0.25
      yaw_goal_tolerance: 0.25
    FollowPath:
      plugin: "nav2_mppi_controller::MPPIController"
      time_steps: 56
      model_dt: 0.05
      batch_size: 2000
      ax_max: 3.0
      ax_min: -3.0
      ay_max: 3.0
      az_max: 3.5
      vx_std: 0.2
      vy_std: 0.2
      wz_std: 0.4
      vx_max: 0.5
      vx_min: -0.35
      vy_max: 0.5
      wz_max: 1.9
      iteration_count: 1
      prune_distance: 1.7
      transform_tolerance: 0.1
      temperature: 0.3
      gamma: 0.015
      motion_model: "DiffDrive"
      visualize: true
      regenerate_noises: true
      TrajectoryVisualizer:
        trajectory_step: 5
        time_step: 3
      AckermannConstraints:
        min_turning_r: 0.2
      critics: [
        "ConstraintCritic", "CostCritic", "GoalCritic",
        "GoalAngleCritic", "PathAlignCritic", "PathFollowCritic",
        "PathAngleCritic", "PreferForwardCritic"]
      ConstraintCritic:
        enabled: true
        cost_power: 1
        cost_weight: 4.0
      GoalCritic:
        enabled: true
        cost_power: 1
        cost_weight: 5.0
        threshold_to_consider: 1.4
      GoalAngleCritic:
        enabled: true
        cost_power: 1
        cost_weight: 3.0
        threshold_to_consider: 0.5
      PreferForwardCritic:
        enabled: true
        cost_power: 1
        cost_weight: 5.0
        threshold_to_consider: 0.5
      CostCritic:
        enabled: true
        cost_power: 1
        cost_weight: 3.81
        critical_cost: 300.0
        consider_footprint: true
        collision_cost: 1000000.0
        near_goal_distance: 1.0
        trajectory_point_step: 2
      PathAlignCritic:
        enabled: true
        cost_power: 1
        cost_weight: 14.0
        max_path_occupancy_ratio: 0.05
        trajectory_point_step: 4
        threshold_to_consider: 0.5
        offset_from_furthest: 20
        use_path_orientations: false
      PathFollowCritic:
        enabled: true
        cost_power: 1
        cost_weight: 5.0
        offset_from_furthest: 5
        threshold_to_consider: 1.4
      PathAngleCritic:
        enabled: true
        cost_power: 1
        cost_weight: 2.0
        offset_from_furthest: 4
        threshold_to_consider: 0.5
        max_angle_to_furthest: 1.0
        mode: 0
      # TwirlingCritic:
      #   enabled: true
      #   twirling_cost_power: 1
      #   twirling_cost_weight: 10.0

local_costmap:
  local_costmap:
    ros__parameters:
      update_frequency: 5.0
      publish_frequency: 2.0
      global_frame: odom
      robot_base_frame: base_link
      rolling_window: true
      width: 3
      height: 3
      resolution: 0.05
      robot_radius: 0.22
      plugins: ["voxel_layer", "inflation_layer"]
      inflation_layer:
        plugin: "nav2_costmap_2d::InflationLayer"
        cost_scaling_factor: 3.0
        inflation_radius: 0.70
      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
      always_send_full_costmap: True

global_costmap:
  global_costmap:
    ros__parameters:
      update_frequency: 1.0
      publish_frequency: 1.0
      global_frame: map     # 全局坐标系
      robot_base_frame: base_link   # 底盘坐标系
      robot_radius: 0.22
      resolution: 0.05
      track_unknown_space: true
      plugins: ["static_layer", "obstacle_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
      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.25
      always_send_full_costmap: True

# The yaml_filename does not need to be specified since it going to be set by defaults in launch.
# If you'd rather set it in the yaml, remove the default "map" value in the tb3_simulation_launch.py
# file & provide full path to map below. If CLI map configuration or launch default is provided, that will be used.
# map_server:
#   ros__parameters:
#     yaml_filename: ""

map_saver:
  ros__parameters:
    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
    planner_plugins: ["GridBased"]
    GridBased:
      plugin: "nav2_navfn_planner::NavfnPlanner"
      tolerance: 0.5
      use_astar: false
      allow_unknown: true

smoother_server:
  ros__parameters:
    smoother_plugins: ["simple_smoother"]
    simple_smoother:
      plugin: "nav2_smoother::SimpleSmoother"
      tolerance: 1.0e-10
      max_its: 1000
      do_refinement: True

behavior_server:
  ros__parameters:
    local_costmap_topic: local_costmap/costmap_raw
    global_costmap_topic: global_costmap/costmap_raw
    local_footprint_topic: local_costmap/published_footprint
    global_footprint_topic: global_costmap/published_footprint
    cycle_frequency: 10.0
    behavior_plugins: ["spin", "backup", "drive_on_heading", "assisted_teleop", "wait"]
    spin:
      plugin: "nav2_behaviors::Spin"
    backup:
      plugin: "nav2_behaviors::BackUp"
    drive_on_heading:
      plugin: "nav2_behaviors::DriveOnHeading"
    wait:
      plugin: "nav2_behaviors::Wait"
    assisted_teleop:
      plugin: "nav2_behaviors::AssistedTeleop"
    local_frame: odom
    global_frame: map
    robot_base_frame: base_link
    transform_tolerance: 0.1
    simulate_ahead_time: 2.0
    max_rotational_vel: 1.0
    min_rotational_vel: 0.4
    rotational_acc_lim: 3.2

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

velocity_smoother:
  ros__parameters:
    smoothing_frequency: 20.0
    scale_velocities: False
    feedback: "OPEN_LOOP"
    max_velocity: [0.5, 0.0, 2.0]
    min_velocity: [-0.5, 0.0, -2.0]
    max_accel: [2.5, 0.0, 3.2]
    max_decel: [-2.5, 0.0, -3.2]
    odom_topic: "odom"
    odom_duration: 0.1
    deadband_velocity: [0.0, 0.0, 0.0]
    velocity_timeout: 1.0

collision_monitor:
  ros__parameters:
    base_frame_id: "base_link"
    odom_frame_id: "odom"
    cmd_vel_in_topic: "cmd_vel_smoothed"
    cmd_vel_out_topic: "cmd_vel"
    state_topic: "collision_monitor_state"
    transform_tolerance: 0.2
    source_timeout: 1.0
    base_shift_correction: True
    stop_pub_timeout: 2.0
    # Polygons represent zone around the robot for "stop", "slowdown" and "limit" action types,
    # and robot footprint for "approach" action type.
    polygons: ["FootprintApproach"]
    FootprintApproach:
      type: "polygon"
      action_type: "approach"
      footprint_topic: "/local_costmap/published_footprint"
      time_before_collision: 1.2
      simulation_time_step: 0.1
      min_points: 6
      visualize: False
      enabled: True
    observation_sources: ["scan"]
    scan:
      type: "scan"
      topic: "scan"
      min_height: 0.15
      max_height: 2.0
      enabled: True

docking_server:
  ros__parameters:
    controller_frequency: 50.0
    initial_perception_timeout: 5.0
    wait_charge_timeout: 5.0
    dock_approach_timeout: 30.0
    undock_linear_tolerance: 0.05
    undock_angular_tolerance: 0.1
    max_retries: 3
    base_frame: "base_link"
    fixed_frame: "odom"
    dock_backwards: false
    dock_prestaging_tolerance: 0.5

    # Types of docks
    dock_plugins: ['simple_charging_dock']
    simple_charging_dock:
      plugin: 'opennav_docking::SimpleChargingDock'
      docking_threshold: 0.05
      staging_x_offset: -0.7
      use_external_detection_pose: true
      use_battery_status: false # true
      use_stall_detection: false # true

      external_detection_timeout: 1.0
      external_detection_translation_x: -0.18
      external_detection_translation_y: 0.0
      external_detection_rotation_roll: -1.57
      external_detection_rotation_pitch: -1.57
      external_detection_rotation_yaw: 0.0
      filter_coef: 0.1

    # Dock instances
    # The following example illustrates configuring dock instances.
    # docks: ['home_dock']  # Input your docks here
    # home_dock:
    #   type: 'simple_charging_dock'
    #   frame: map
    #   pose: [0.0, 0.0, 0.0]

    controller:
      k_phi: 3.0
      k_delta: 2.0
      v_linear_min: 0.15
      v_linear_max: 0.15

logs

After I start navigation2, the following log file is displayed. As you can see, there is no map coordinate frame.

r@r:~$ ros2 launch robot_nav robot_nav.launch.py 
[INFO] [launch]: All log files can be found below /home/r/.ros/log/2024-08-02-11-21-06-247164-r-78476
[INFO] [launch]: Default logging verbosity is set to INFO
[INFO] [component_container_isolated-1]: process started with pid [78495]
[component_container_isolated-1] [INFO] [1722568867.211811542] [nav2_container]: Load Library: /opt/ros/jazzy/lib/libmap_server_core.so
[component_container_isolated-1] [INFO] [1722568867.225767978] [nav2_container]: Found class: rclcpp_components::NodeFactoryTemplate<nav2_map_server::CostmapFilterInfoServer>
[component_container_isolated-1] [INFO] [1722568867.225809395] [nav2_container]: Found class: rclcpp_components::NodeFactoryTemplate<nav2_map_server::MapSaver>
[component_container_isolated-1] [INFO] [1722568867.225818282] [nav2_container]: Found class: rclcpp_components::NodeFactoryTemplate<nav2_map_server::MapServer>
[component_container_isolated-1] [INFO] [1722568867.225825664] [nav2_container]: Instantiate class: rclcpp_components::NodeFactoryTemplate<nav2_map_server::MapServer>
[component_container_isolated-1] [INFO] [1722568867.242930016] [map_server]: 
[component_container_isolated-1]    map_server lifecycle node launched. 
[component_container_isolated-1]    Waiting on external lifecycle transitions to activate
[component_container_isolated-1]    See https://design.ros2.org/articles/node_lifecycle.html for more information.
[component_container_isolated-1] [INFO] [1722568867.242968913] [map_server]: Creating
[INFO] [launch_ros.actions.load_composable_nodes]: Loaded node '/map_server' in container '/nav2_container'
[component_container_isolated-1] [INFO] [1722568867.243536240] [nav2_container]: Load Library: /opt/ros/jazzy/lib/libamcl_core.so
[component_container_isolated-1] [INFO] [1722568867.247296965] [nav2_container]: Found class: rclcpp_components::NodeFactoryTemplate<nav2_amcl::AmclNode>
[component_container_isolated-1] [INFO] [1722568867.247379699] [nav2_container]: Instantiate class: rclcpp_components::NodeFactoryTemplate<nav2_amcl::AmclNode>
[component_container_isolated-1] [INFO] [1722568867.257992810] [amcl]: 
[component_container_isolated-1]    amcl lifecycle node launched. 
[component_container_isolated-1]    Waiting on external lifecycle transitions to activate
[component_container_isolated-1]    See https://design.ros2.org/articles/node_lifecycle.html for more information.
[component_container_isolated-1] [INFO] [1722568867.258443399] [amcl]: Creating
[INFO] [launch_ros.actions.load_composable_nodes]: Loaded node '/amcl' in container '/nav2_container'
[component_container_isolated-1] [INFO] [1722568867.266831145] [nav2_container]: Load Library: /opt/ros/jazzy/lib/libcontroller_server_core.so
[component_container_isolated-1] [INFO] [1722568867.272093851] [nav2_container]: Found class: rclcpp_components::NodeFactoryTemplate<nav2_controller::ControllerServer>
[component_container_isolated-1] [INFO] [1722568867.272125669] [nav2_container]: Instantiate class: rclcpp_components::NodeFactoryTemplate<nav2_controller::ControllerServer>
[component_container_isolated-1] [INFO] [1722568867.290812105] [controller_server]: 
[component_container_isolated-1]    controller_server lifecycle node launched. 
[component_container_isolated-1]    Waiting on external lifecycle transitions to activate
[component_container_isolated-1]    See https://design.ros2.org/articles/node_lifecycle.html for more information.
[component_container_isolated-1] [INFO] [1722568867.297086996] [controller_server]: Creating controller server
[component_container_isolated-1] [INFO] [1722568867.332466998] [local_costmap.local_costmap]: 
[component_container_isolated-1]    local_costmap lifecycle node launched. 
[component_container_isolated-1]    Waiting on external lifecycle transitions to activate
[component_container_isolated-1]    See https://design.ros2.org/articles/node_lifecycle.html for more information.
[component_container_isolated-1] [INFO] [1722568867.333151872] [local_costmap.local_costmap]: Creating Costmap
[INFO] [launch_ros.actions.load_composable_nodes]: Loaded node '/controller_server' in container '/nav2_container'
[component_container_isolated-1] [INFO] [1722568867.341121484] [nav2_container]: Load Library: /opt/ros/jazzy/lib/libnav2_lifecycle_manager_core.so
[component_container_isolated-1] [INFO] [1722568867.342169117] [nav2_container]: Found class: rclcpp_components::NodeFactoryTemplate<nav2_lifecycle_manager::LifecycleManager>
[component_container_isolated-1] [INFO] [1722568867.342186986] [nav2_container]: Instantiate class: rclcpp_components::NodeFactoryTemplate<nav2_lifecycle_manager::LifecycleManager>
[component_container_isolated-1] [INFO] [1722568867.354258731] [lifecycle_manager_localization]: Creating
[INFO] [launch_ros.actions.load_composable_nodes]: Loaded node '/lifecycle_manager_localization' in container '/nav2_container'
[component_container_isolated-1] [INFO] [1722568867.358583819] [lifecycle_manager_localization]: Creating and initializing lifecycle service clients
[component_container_isolated-1] [INFO] [1722568867.358652833] [nav2_container]: Load Library: /opt/ros/jazzy/lib/libsmoother_server_core.so
[component_container_isolated-1] [INFO] [1722568867.360643781] [nav2_container]: Found class: rclcpp_components::NodeFactoryTemplate<nav2_smoother::SmootherServer>
[component_container_isolated-1] [INFO] [1722568867.360663862] [nav2_container]: Instantiate class: rclcpp_components::NodeFactoryTemplate<nav2_smoother::SmootherServer>
[component_container_isolated-1] [INFO] [1722568867.370643699] [lifecycle_manager_localization]: Starting managed nodes bringup...
[component_container_isolated-1] [INFO] [1722568867.370706598] [lifecycle_manager_localization]: Configuring map_server
[component_container_isolated-1] [INFO] [1722568867.370894156] [map_server]: Configuring
[component_container_isolated-1] [INFO] [map_io]: Loading yaml file: /home/r/robot_ws/install/robot_nav/share/robot_nav/maps/map.yaml
[component_container_isolated-1] [DEBUG] [map_io]: resolution: 0.05
[component_container_isolated-1] [DEBUG] [map_io]: origin[0]: -10
[component_container_isolated-1] [DEBUG] [map_io]: origin[1]: -10
[component_container_isolated-1] [DEBUG] [map_io]: origin[2]: 0
[component_container_isolated-1] [DEBUG] [map_io]: free_thresh: 0.25
[component_container_isolated-1] [DEBUG] [map_io]: occupied_thresh: 0.65
[component_container_isolated-1] [DEBUG] [map_io]: mode: trinary
[component_container_isolated-1] [DEBUG] [map_io]: negate: 0
[component_container_isolated-1] [INFO] [map_io]: Loading image_file: /home/r/robot_ws/install/robot_nav/share/robot_nav/maps/map.pgm
[component_container_isolated-1] [DEBUG] [map_io]: Read map /home/r/robot_ws/install/robot_nav/share/robot_nav/maps/map.pgm: 384 X 384 map @ 0.05 m/cell
[component_container_isolated-1] [INFO] [1722568867.395039443] [lifecycle_manager_localization]: Configuring amcl
[component_container_isolated-1] [INFO] [1722568867.395182273] [amcl]: Configuring
[component_container_isolated-1] [INFO] [1722568867.395277584] [amcl]: initTransforms
[component_container_isolated-1] [INFO] [1722568867.436122285] [smoother_server]: 
[component_container_isolated-1]    smoother_server lifecycle node launched. 
[component_container_isolated-1]    Waiting on external lifecycle transitions to activate
[component_container_isolated-1]    See https://design.ros2.org/articles/node_lifecycle.html for more information.
[component_container_isolated-1] [INFO] [1722568867.438982917] [smoother_server]: Creating smoother server
[INFO] [launch_ros.actions.load_composable_nodes]: Loaded node '/smoother_server' in container '/nav2_container'
[component_container_isolated-1] [INFO] [1722568867.443077189] [nav2_container]: Load Library: /opt/ros/jazzy/lib/libplanner_server_core.so
[component_container_isolated-1] [INFO] [1722568867.443532664] [amcl]: initPubSub
[component_container_isolated-1] [INFO] [1722568867.444273414] [nav2_container]: Found class: rclcpp_components::NodeFactoryTemplate<nav2_planner::PlannerServer>
[component_container_isolated-1] [INFO] [1722568867.444294316] [nav2_container]: Instantiate class: rclcpp_components::NodeFactoryTemplate<nav2_planner::PlannerServer>
[component_container_isolated-1] [INFO] [1722568867.469510739] [amcl]: Subscribed to map topic.
[component_container_isolated-1] [INFO] [1722568867.496411505] [lifecycle_manager_localization]: Activating map_server
[component_container_isolated-1] [INFO] [1722568867.496511627] [map_server]: Activating
[component_container_isolated-1] [INFO] [1722568867.496804363] [map_server]: Creating bond (map_server) to lifecycle manager.
[component_container_isolated-1] [INFO] [1722568867.496972710] [amcl]: Received a 384 X 384 map @ 0.050 m/pix
[component_container_isolated-1] [INFO] [1722568867.508048514] [planner_server]: 
[component_container_isolated-1]    planner_server lifecycle node launched. 
[component_container_isolated-1]    Waiting on external lifecycle transitions to activate
[component_container_isolated-1]    See https://design.ros2.org/articles/node_lifecycle.html for more information.
[component_container_isolated-1] [INFO] [1722568867.509920816] [planner_server]: Creating
[component_container_isolated-1] [INFO] [1722568867.570348941] [global_costmap.global_costmap]: 
[component_container_isolated-1]    global_costmap lifecycle node launched. 
[component_container_isolated-1]    Waiting on external lifecycle transitions to activate
[component_container_isolated-1]    See https://design.ros2.org/articles/node_lifecycle.html for more information.
[component_container_isolated-1] [INFO] [1722568867.570781326] [global_costmap.global_costmap]: Creating Costmap
[INFO] [launch_ros.actions.load_composable_nodes]: Loaded node '/planner_server' in container '/nav2_container'
[component_container_isolated-1] [INFO] [1722568867.575827431] [nav2_container]: Load Library: /opt/ros/jazzy/lib/libbehavior_server_core.so
[component_container_isolated-1] [INFO] [1722568867.576711987] [nav2_container]: Found class: rclcpp_components::NodeFactoryTemplate<behavior_server::BehaviorServer>
[component_container_isolated-1] [INFO] [1722568867.576727498] [nav2_container]: Instantiate class: rclcpp_components::NodeFactoryTemplate<behavior_server::BehaviorServer>
[component_container_isolated-1] [INFO] [1722568867.608902751] [lifecycle_manager_localization]: Server map_server connected with bond.
[component_container_isolated-1] [INFO] [1722568867.608931184] [lifecycle_manager_localization]: Activating amcl
[component_container_isolated-1] [INFO] [1722568867.609104110] [amcl]: Activating
[component_container_isolated-1] [INFO] [1722568867.609129326] [amcl]: Creating bond (amcl) to lifecycle manager.
[component_container_isolated-1] [INFO] [1722568867.617009788] [amcl]: createLaserObject
[component_container_isolated-1] [INFO] [1722568867.625297096] [behavior_server]: 
[component_container_isolated-1]    behavior_server lifecycle node launched. 
[component_container_isolated-1]    Waiting on external lifecycle transitions to activate
[component_container_isolated-1]    See https://design.ros2.org/articles/node_lifecycle.html for more information.
[INFO] [launch_ros.actions.load_composable_nodes]: Loaded node '/behavior_server' in container '/nav2_container'
[component_container_isolated-1] [INFO] [1722568867.630013773] [nav2_container]: Load Library: /opt/ros/jazzy/lib/libbt_navigator_core.so
[component_container_isolated-1] [INFO] [1722568867.630964980] [nav2_container]: Found class: rclcpp_components::NodeFactoryTemplate<nav2_bt_navigator::BtNavigator>
[component_container_isolated-1] [INFO] [1722568867.630980345] [nav2_container]: Instantiate class: rclcpp_components::NodeFactoryTemplate<nav2_bt_navigator::BtNavigator>
[component_container_isolated-1] [INFO] [1722568867.689596053] [bt_navigator]: 
[component_container_isolated-1]    bt_navigator lifecycle node launched. 
[component_container_isolated-1]    Waiting on external lifecycle transitions to activate
[component_container_isolated-1]    See https://design.ros2.org/articles/node_lifecycle.html for more information.
[component_container_isolated-1] [INFO] [1722568867.691549171] [bt_navigator]: Creating
[INFO] [launch_ros.actions.load_composable_nodes]: Loaded node '/bt_navigator' in container '/nav2_container'
[component_container_isolated-1] [INFO] [1722568867.693147964] [nav2_container]: Load Library: /opt/ros/jazzy/lib/libwaypoint_follower_core.so
[component_container_isolated-1] [INFO] [1722568867.694353745] [nav2_container]: Found class: rclcpp_components::NodeFactoryTemplate<nav2_waypoint_follower::WaypointFollower>
[component_container_isolated-1] [INFO] [1722568867.694369745] [nav2_container]: Instantiate class: rclcpp_components::NodeFactoryTemplate<nav2_waypoint_follower::WaypointFollower>
[component_container_isolated-1] [INFO] [1722568867.726664080] [lifecycle_manager_localization]: Server amcl connected with bond.
[component_container_isolated-1] [INFO] [1722568867.726748447] [lifecycle_manager_localization]: Managed nodes are active
[component_container_isolated-1] [INFO] [1722568867.726765432] [lifecycle_manager_localization]: Creating bond timer...
[component_container_isolated-1] [INFO] [1722568867.729952487] [waypoint_follower]: 
[component_container_isolated-1]    waypoint_follower lifecycle node launched. 
[component_container_isolated-1]    Waiting on external lifecycle transitions to activate
[component_container_isolated-1]    See https://design.ros2.org/articles/node_lifecycle.html for more information.
[component_container_isolated-1] [INFO] [1722568867.730624637] [waypoint_follower]: Creating
[INFO] [launch_ros.actions.load_composable_nodes]: Loaded node '/waypoint_follower' in container '/nav2_container'
[component_container_isolated-1] [INFO] [1722568867.733126906] [nav2_container]: Load Library: /opt/ros/jazzy/lib/libvelocity_smoother_core.so
[component_container_isolated-1] [INFO] [1722568867.733981493] [nav2_container]: Found class: rclcpp_components::NodeFactoryTemplate<nav2_velocity_smoother::VelocitySmoother>
[component_container_isolated-1] [INFO] [1722568867.733995163] [nav2_container]: Instantiate class: rclcpp_components::NodeFactoryTemplate<nav2_velocity_smoother::VelocitySmoother>
[component_container_isolated-1] [INFO] [1722568867.805585345] [velocity_smoother]: 
[component_container_isolated-1]    velocity_smoother lifecycle node launched. 
[INFO] [launch_ros.actions.load_composable_nodes]: Loaded node '/velocity_smoother' in container '/nav2_container'
[component_container_isolated-1]    Waiting on external lifecycle transitions to activate
[component_container_isolated-1]    See https://design.ros2.org/articles/node_lifecycle.html for more information.
[component_container_isolated-1] [INFO] [1722568867.807998162] [nav2_container]: Load Library: /opt/ros/jazzy/lib/libcollision_monitor_core.so
[component_container_isolated-1] [INFO] [1722568867.810911768] [nav2_container]: Found class: rclcpp_components::NodeFactoryTemplate<nav2_collision_monitor::CollisionMonitor>
[component_container_isolated-1] [INFO] [1722568867.810934063] [nav2_container]: Instantiate class: rclcpp_components::NodeFactoryTemplate<nav2_collision_monitor::CollisionMonitor>
[component_container_isolated-1] [INFO] [1722568867.871370144] [collision_monitor]: 
[component_container_isolated-1]    collision_monitor lifecycle node launched. 
[component_container_isolated-1]    Waiting on external lifecycle transitions to activate
[component_container_isolated-1]    See https://design.ros2.org/articles/node_lifecycle.html for more information.
[INFO] [launch_ros.actions.load_composable_nodes]: Loaded node '/collision_monitor' in container '/nav2_container'
[component_container_isolated-1] [INFO] [1722568867.873455064] [nav2_container]: Load Library: /opt/ros/jazzy/lib/libopennav_docking_core.so
[component_container_isolated-1] [INFO] [1722568867.874833968] [nav2_container]: Found class: rclcpp_components::NodeFactoryTemplate<opennav_docking::DockingServer>
[component_container_isolated-1] [INFO] [1722568867.874866763] [nav2_container]: Instantiate class: rclcpp_components::NodeFactoryTemplate<opennav_docking::DockingServer>
[component_container_isolated-1] [INFO] [1722568867.937446662] [docking_server]: 
[component_container_isolated-1]    docking_server lifecycle node launched. 
[component_container_isolated-1]    Waiting on external lifecycle transitions to activate
[component_container_isolated-1]    See https://design.ros2.org/articles/node_lifecycle.html for more information.
[component_container_isolated-1] [INFO] [1722568867.937482372] [docking_server]: Creating docking_server
[INFO] [launch_ros.actions.load_composable_nodes]: Loaded node '/docking_server' in container '/nav2_container'
[component_container_isolated-1] [INFO] [1722568867.940554786] [nav2_container]: Found class: rclcpp_components::NodeFactoryTemplate<nav2_lifecycle_manager::LifecycleManager>
[component_container_isolated-1] [INFO] [1722568867.940580003] [nav2_container]: Instantiate class: rclcpp_components::NodeFactoryTemplate<nav2_lifecycle_manager::LifecycleManager>
[component_container_isolated-1] [INFO] [1722568867.993825952] [lifecycle_manager_navigation]: Creating
[INFO] [launch_ros.actions.load_composable_nodes]: Loaded node '/lifecycle_manager_navigation' in container '/nav2_container'
[component_container_isolated-1] [INFO] [1722568868.003022875] [lifecycle_manager_navigation]: Creating and initializing lifecycle service clients
[component_container_isolated-1] [INFO] [1722568868.070790710] [lifecycle_manager_navigation]: Starting managed nodes bringup...
[component_container_isolated-1] [INFO] [1722568868.070822912] [lifecycle_manager_navigation]: Configuring controller_server
[component_container_isolated-1] [INFO] [1722568868.070991942] [controller_server]: Configuring controller interface
[component_container_isolated-1] [INFO] [1722568868.071013241] [controller_server]: getting progress checker plugins..
[component_container_isolated-1] [INFO] [1722568868.071272740] [controller_server]: getting goal checker plugins..
[component_container_isolated-1] [INFO] [1722568868.071460762] [controller_server]: Controller frequency set to 20.0000Hz
[component_container_isolated-1] [INFO] [1722568868.071498103] [local_costmap.local_costmap]: Configuring
[component_container_isolated-1] [INFO] [1722568868.093244496] [local_costmap.local_costmap]: Using plugin "voxel_layer"
[component_container_isolated-1] [INFO] [1722568868.096494696] [local_costmap.local_costmap]: Subscribed to Topics: scan
[component_container_isolated-1] [INFO] [1722568868.121369694] [local_costmap.local_costmap]: Initialized plugin "voxel_layer"
[component_container_isolated-1] [INFO] [1722568868.121400126] [local_costmap.local_costmap]: Using plugin "inflation_layer"
[component_container_isolated-1] [INFO] [1722568868.122418794] [local_costmap.local_costmap]: Initialized plugin "inflation_layer"
[component_container_isolated-1] [INFO] [1722568868.196653861] [controller_server]: Created progress_checker : progress_checker of type nav2_controller::SimpleProgressChecker
[component_container_isolated-1] [INFO] [1722568868.197139483] [controller_server]: Controller Server has progress_checker  progress checkers available.
[component_container_isolated-1] [INFO] [1722568868.197863836] [controller_server]: Created goal checker : general_goal_checker of type nav2_controller::SimpleGoalChecker
[component_container_isolated-1] [INFO] [1722568868.198410931] [controller_server]: Controller Server has general_goal_checker  goal checkers available.
[component_container_isolated-1] [INFO] [1722568868.200005705] [controller_server]: Created controller : FollowPath of type nav2_mppi_controller::MPPIController
[component_container_isolated-1] [INFO] [1722568868.203914858] [controller_server]: Controller period is equal to model dt. Control sequence shifting is ON
[component_container_isolated-1] [INFO] [1722568868.206235652] [controller_server]: ConstraintCritic instantiated with 1 power and 4.000000 weight.
[component_container_isolated-1] [INFO] [1722568868.206262522] [controller_server]: Critic loaded : mppi::critics::ConstraintCritic
[component_container_isolated-1] [INFO] [1722568868.207839937] [controller_server]: InflationCostCritic instantiated with 1 power and 300.000000 / 0.015000 weights. Critic will collision check based on footprint cost.
[component_container_isolated-1] [INFO] [1722568868.207875660] [controller_server]: Critic loaded : mppi::critics::CostCritic
[component_container_isolated-1] [INFO] [1722568868.208652059] [controller_server]: GoalCritic instantiated with 1 power and 5.000000 weight.
[component_container_isolated-1] [INFO] [1722568868.208673221] [controller_server]: Critic loaded : mppi::critics::GoalCritic
[component_container_isolated-1] [INFO] [1722568868.209355179] [controller_server]: GoalAngleCritic instantiated with 1 power, 3.000000 weight, and 0.500000 angular threshold.
[component_container_isolated-1] [INFO] [1722568868.209374019] [controller_server]: Critic loaded : mppi::critics::GoalAngleCritic
[component_container_isolated-1] [INFO] [1722568868.210704773] [controller_server]: ReferenceTrajectoryCritic instantiated with 1 power and 14.000000 weight
[component_container_isolated-1] [INFO] [1722568868.210724959] [controller_server]: Critic loaded : mppi::critics::PathAlignCritic
[component_container_isolated-1] [INFO] [1722568868.211568557] [controller_server]: Critic loaded : mppi::critics::PathFollowCritic
[component_container_isolated-1] [INFO] [1722568868.212740337] [controller_server]: PathAngleCritic instantiated with 1 power and 2.000000 weight. Mode set to: Forward Preference
[component_container_isolated-1] [INFO] [1722568868.212759116] [controller_server]: Critic loaded : mppi::critics::PathAngleCritic
[component_container_isolated-1] [INFO] [1722568868.213446368] [controller_server]: PreferForwardCritic instantiated with 1 power and 5.000000 weight.
[component_container_isolated-1] [INFO] [1722568868.213463093] [controller_server]: Critic loaded : mppi::critics::PreferForwardCritic
[component_container_isolated-1] [INFO] [1722568868.215886952] [controller_server]: Optimizer reset
[component_container_isolated-1] [INFO] [1722568868.226530953] [MPPIController]: Configured MPPI Controller: FollowPath
[component_container_isolated-1] [INFO] [1722568868.226549218] [controller_server]: Controller Server has FollowPath  controllers available.
[component_container_isolated-1] [INFO] [1722568868.256972490] [lifecycle_manager_navigation]: Configuring smoother_server
[component_container_isolated-1] [INFO] [1722568868.257082477] [smoother_server]: Configuring smoother server
[component_container_isolated-1] [INFO] [1722568868.279578843] [smoother_server]: Created smoother : simple_smoother of type nav2_smoother::SimpleSmoother
[component_container_isolated-1] [INFO] [1722568868.280948208] [smoother_server]: Smoother Server has simple_smoother  smoothers available.
[component_container_isolated-1] [INFO] [1722568868.309888897] [lifecycle_manager_navigation]: Configuring planner_server
[component_container_isolated-1] [INFO] [1722568868.310034335] [planner_server]: Configuring
[component_container_isolated-1] [INFO] [1722568868.310062532] [global_costmap.global_costmap]: Configuring
[component_container_isolated-1] [INFO] [1722568868.330736446] [global_costmap.global_costmap]: Using plugin "static_layer"
[component_container_isolated-1] [INFO] [1722568868.331909752] [global_costmap.global_costmap]: Subscribing to the map topic (/map) with transient local durability
[component_container_isolated-1] [INFO] [1722568868.332872870] [global_costmap.global_costmap]: Initialized plugin "static_layer"
[component_container_isolated-1] [INFO] [1722568868.332890276] [global_costmap.global_costmap]: Using plugin "obstacle_layer"
[component_container_isolated-1] [INFO] [1722568868.334214626] [global_costmap.global_costmap]: Subscribed to Topics: scan
[component_container_isolated-1] [INFO] [1722568868.353186998] [global_costmap.global_costmap]: Initialized plugin "obstacle_layer"
[component_container_isolated-1] [INFO] [1722568868.353211384] [global_costmap.global_costmap]: Using plugin "inflation_layer"
[component_container_isolated-1] [INFO] [1722568868.354139501] [global_costmap.global_costmap]: Initialized plugin "inflation_layer"
[component_container_isolated-1] [INFO] [1722568868.433493238] [global_costmap.global_costmap]: StaticLayer: Resizing costmap to 384 X 384 at 0.050000 m/pix
[component_container_isolated-1] [INFO] [1722568868.434030959] [planner_server]: Created global planner plugin GridBased of type nav2_navfn_planner::NavfnPlanner
[component_container_isolated-1] [INFO] [1722568868.434052440] [planner_server]: Configuring plugin GridBased of type NavfnPlanner
[component_container_isolated-1] [INFO] [1722568868.435128154] [planner_server]: Planner Server has GridBased  planners available.
[component_container_isolated-1] [INFO] [1722568868.504787615] [lifecycle_manager_navigation]: Configuring behavior_server
[component_container_isolated-1] [INFO] [1722568868.504930898] [behavior_server]: Configuring
[component_container_isolated-1] [INFO] [1722568868.557640639] [behavior_server]: Creating behavior plugin spin of type nav2_behaviors::Spin
[component_container_isolated-1] [INFO] [1722568868.558920956] [behavior_server]: Creating behavior plugin backup of type nav2_behaviors::BackUp
[component_container_isolated-1] [INFO] [1722568868.560156231] [behavior_server]: Creating behavior plugin drive_on_heading of type nav2_behaviors::DriveOnHeading
[component_container_isolated-1] [INFO] [1722568868.561535670] [behavior_server]: Creating behavior plugin assisted_teleop of type nav2_behaviors::AssistedTeleop
[component_container_isolated-1] [INFO] [1722568868.563827521] [behavior_server]: Creating behavior plugin wait of type nav2_behaviors::Wait
[component_container_isolated-1] [INFO] [1722568868.585910372] [behavior_server]: Configuring spin
[component_container_isolated-1] [INFO] [1722568868.619605901] [behavior_server]: Configuring backup
[component_container_isolated-1] [INFO] [1722568868.644124282] [behavior_server]: Configuring drive_on_heading
[component_container_isolated-1] [INFO] [1722568868.676108831] [behavior_server]: Configuring assisted_teleop
[component_container_isolated-1] [INFO] [1722568868.704176984] [behavior_server]: Configuring wait
[component_container_isolated-1] [INFO] [1722568868.750788097] [lifecycle_manager_navigation]: Configuring velocity_smoother
[component_container_isolated-1] [INFO] [1722568868.750911283] [velocity_smoother]: Configuring velocity smoother
[component_container_isolated-1] [INFO] [1722568868.762631426] [lifecycle_manager_navigation]: Configuring collision_monitor
[component_container_isolated-1] [INFO] [1722568868.762785032] [collision_monitor]: Configuring
[component_container_isolated-1] [INFO] [1722568868.787114487] [collision_monitor]: [FootprintApproach]: Creating Polygon
[component_container_isolated-1] [INFO] [1722568868.787330937] [collision_monitor]: [FootprintApproach]: Polygon points are not defined. Using dynamic subscription instead.
[component_container_isolated-1] [INFO] [1722568868.795427104] [collision_monitor]: [FootprintApproach]: Making footprint subscriber on /local_costmap/published_footprint topic
[component_container_isolated-1] [INFO] [1722568868.803346149] [collision_monitor]: [scan]: Creating Scan
[component_container_isolated-1] [INFO] [1722568868.822939915] [lifecycle_manager_navigation]: Configuring bt_navigator
[component_container_isolated-1] [INFO] [1722568868.823076596] [bt_navigator]: Configuring
[component_container_isolated-1] [INFO] [1722568868.842099845] [bt_navigator]: Creating navigator id navigate_to_pose of type nav2_bt_navigator::NavigateToPoseNavigator
[component_container_isolated-1] [INFO] [1722568869.000861550] [bt_navigator]: Creating navigator id navigate_through_poses of type nav2_bt_navigator::NavigateThroughPosesNavigator
[component_container_isolated-1] [INFO] [1722568869.101040593] [lifecycle_manager_navigation]: Configuring waypoint_follower
[component_container_isolated-1] [INFO] [1722568869.101155125] [waypoint_follower]: Configuring
[component_container_isolated-1] [INFO] [1722568869.191089084] [waypoint_follower]: Created waypoint_task_executor : wait_at_waypoint of type nav2_waypoint_follower::WaitAtWaypoint
[component_container_isolated-1] [INFO] [1722568869.192037196] [lifecycle_manager_navigation]: Configuring docking_server
[component_container_isolated-1] [INFO] [1722568869.192182032] [docking_server]: Configuring docking_server
[component_container_isolated-1] [INFO] [1722568869.192217626] [docking_server]: Controller frequency set to 50.0000Hz
[component_container_isolated-1] [INFO] [1722568869.256482796] [docking_server]: Created charging dock plugin simple_charging_dock of type opennav_docking::SimpleChargingDock
[component_container_isolated-1] [WARN] [1722568869.284035109] [docking_server]: Dock database filepath nor dock parameters set. Docking actions can only be executed specifying the dock pose via the action request. Or update the dock database via the reload_database service.
[component_container_isolated-1] [INFO] [1722568869.284093465] [docking_server]: Docking Server has 1 dock types and 0 dock instances available.
[component_container_isolated-1] [INFO] [1722568869.291341530] [lifecycle_manager_navigation]: Activating controller_server
[component_container_isolated-1] [INFO] [1722568869.291484443] [controller_server]: Activating
[component_container_isolated-1] [INFO] [1722568869.291518174] [local_costmap.local_costmap]: Activating
[component_container_isolated-1] [INFO] [1722568869.291530032] [local_costmap.local_costmap]: Checking transform
[component_container_isolated-1] [INFO] [1722568869.291652037] [local_costmap.local_costmap]: start
[component_container_isolated-1] [WARN] [1722568869.460232746] [amcl]: AMCL cannot publish a pose or update the transform. Please set the initial pose...
[component_container_isolated-1] [WARN] [1722568869.501110628] [controller_server]: Parameter controller_server.verbose not found
[component_container_isolated-1] [INFO] [1722568869.502992680] [controller_server]: Optimizer reset
[component_container_isolated-1] [INFO] [1722568869.503555399] [MPPIController]: Activated MPPI Controller: FollowPath
[component_container_isolated-1] [INFO] [1722568869.503588038] [controller_server]: Creating bond (controller_server) to lifecycle manager.
[component_container_isolated-1] [INFO] [1722568869.617493899] [lifecycle_manager_navigation]: Server controller_server connected with bond.
[component_container_isolated-1] [INFO] [1722568869.617546625] [lifecycle_manager_navigation]: Activating smoother_server
[component_container_isolated-1] [INFO] [1722568869.617908173] [smoother_server]: Activating
[component_container_isolated-1] [INFO] [1722568869.617943316] [smoother_server]: Creating bond (smoother_server) to lifecycle manager.
[component_container_isolated-1] [INFO] [1722568869.726465038] [lifecycle_manager_navigation]: Server smoother_server connected with bond.
[component_container_isolated-1] [INFO] [1722568869.726496207] [lifecycle_manager_navigation]: Activating planner_server
[component_container_isolated-1] [INFO] [1722568869.726741453] [planner_server]: Activating
[component_container_isolated-1] [INFO] [1722568869.726792934] [global_costmap.global_costmap]: Activating
[component_container_isolated-1] [INFO] [1722568869.726804730] [global_costmap.global_costmap]: Checking transform
[component_container_isolated-1] [INFO] [1722568869.726820184] [global_costmap.global_costmap]: Timed out waiting for transform from base_link to map to become available, tf error: Invalid frame ID "map" passed to canTransform argument target_frame - frame does not exist
[component_container_isolated-1] [INFO] [1722568870.226885015] [global_costmap.global_costmap]: Timed out waiting for transform from base_link to map to become available, tf error: Invalid frame ID "map" passed to canTransform argument target_frame - frame does not exist
[component_container_isolated-1] [INFO] [1722568870.726890954] [global_costmap.global_costmap]: Timed out waiting for transform from base_link to map to become available, tf error: Invalid frame ID "map" passed to canTransform argument target_frame - frame does not exist
[component_container_isolated-1] [INFO] [1722568871.226882274] [global_costmap.global_costmap]: Timed out waiting for transform from base_link to map to become available, tf error: Invalid frame ID "map" passed to canTransform argument target_frame - frame does not exist
[component_container_isolated-1] [WARN] [1722568871.556631750] [amcl]: AMCL cannot publish a pose or update the transform. Please set the initial pose...
[component_container_isolated-1] [INFO] [1722568871.726877143] [global_costmap.global_costmap]: Timed out waiting for transform from base_link to map to become available, tf error: Invalid frame ID "map" passed to canTransform argument target_frame - frame does not exist
[component_container_isolated-1] [INFO] [1722568872.226899009] [global_costmap.global_costmap]: Timed out waiting for transform from base_link to map to become available, tf error: Invalid frame ID "map" passed to canTransform argument target_frame - frame does not exist
[component_container_isolated-1] [INFO] [1722568872.726897272] [global_costmap.global_costmap]: Timed out waiting for transform from base_link to map to become available, tf error: Invalid frame ID "map" passed to canTransform argument target_frame - frame does not exist
[component_container_isolated-1] [INFO] [1722568873.226886912] [global_costmap.global_costmap]: Timed out waiting for transform from base_link to map to become available, tf error: Invalid frame ID "map" passed to canTransform argument target_frame - frame does not exist
[component_container_isolated-1] [WARN] [1722568873.600159008] [amcl]: AMCL cannot publish a pose or update the transform. Please set the initial pose...
[component_container_isolated-1] [INFO] [1722568873.726925841] [global_costmap.global_costmap]: Timed out waiting for transform from base_link to map to become available, tf error: Invalid frame ID "map" passed to canTransform argument target_frame - frame does not exist
[component_container_isolated-1] [INFO] [1722568874.226913923] [global_costmap.global_costmap]: Timed out waiting for transform from base_link to map to become available, tf error: Invalid frame ID "map" passed to canTransform argument target_frame - frame does not exist
[component_container_isolated-1] [INFO] [1722568874.726925061] [global_costmap.global_costmap]: Timed out waiting for transform from base_link to map to become available, tf error: Invalid frame ID "map" passed to canTransform argument target_frame - frame does not exist
[component_container_isolated-1] [INFO] [1722568875.226913467] [global_costmap.global_costmap]: Timed out waiting for transform from base_link to map to become available, tf error: Invalid frame ID "map" passed to canTransform argument target_frame - frame does not exist
[component_container_isolated-1] [WARN] [1722568875.600339613] [amcl]: AMCL cannot publish a pose or update the transform. Please set the initial pose...
[component_container_isolated-1] [INFO] [1722568875.726927867] [global_costmap.global_costmap]: Timed out waiting for transform from base_link to map to become available, tf error: Invalid frame ID "map" passed to canTransform argument target_frame - frame does not exist
[component_container_isolated-1] [INFO] [1722568876.226906460] [global_costmap.global_costmap]: Timed out waiting for transform from base_link to map to become available, tf error: Invalid frame ID "map" passed to canTransform argument target_frame - frame does not exist
[component_container_isolated-1] [INFO] [1722568876.726890365] [global_costmap.global_costmap]: Timed out waiting for transform from base_link to map to become available, tf error: Invalid frame ID "map" passed to canTransform argument target_frame - frame does not exist
[component_container_isolated-1] [INFO] [1722568877.226875244] [global_costmap.global_costmap]: Timed out waiting for transform from base_link to map to become available, tf error: Invalid frame ID "map" passed to canTransform argument target_frame - frame does not exist
[component_container_isolated-1] [WARN] [1722568877.694345652] [amcl]: AMCL cannot publish a pose or update the transform. Please set the initial pose...
[component_container_isolated-1] [INFO] [1722568877.726871679] [global_costmap.global_costmap]: Timed out waiting for transform from base_link to map to become available, tf error: Invalid frame ID "map" passed to canTransform argument target_frame - frame does not exist
[component_container_isolated-1] [INFO] [1722568878.226911709] [global_costmap.global_costmap]: Timed out waiting for transform from base_link to map to become available, tf error: Invalid frame ID "map" passed to canTransform argument target_frame - frame does not exist
[component_container_isolated-1] [INFO] [1722568878.726928116] [global_costmap.global_costmap]: Timed out waiting for transform from base_link to map to become available, tf error: Invalid frame ID "map" passed to canTransform argument target_frame - frame does not exist
[component_container_isolated-1] [INFO] [1722568879.226870990] [global_costmap.global_costmap]: Timed out waiting for transform from base_link to map to become available, tf error: Invalid frame ID "map" passed to canTransform argument target_frame - frame does not exist
[component_container_isolated-1] [INFO] [1722568879.726909406] [global_costmap.global_costmap]: Timed out waiting for transform from base_link to map to become available, tf error: Invalid frame ID "map" passed to canTransform argument target_frame - frame does not exist
[component_container_isolated-1] [WARN] [1722568879.791412967] [amcl]: AMCL cannot publish a pose or update the transform. Please set the initial pose...
[component_container_isolated-1] [INFO] [1722568880.226919950] [global_costmap.global_costmap]: Timed out waiting for transform from base_link to map to become available, tf error: Invalid frame ID "map" passed to canTransform argument target_frame - frame does not exist
[component_container_isolated-1] [INFO] [1722568880.726911217] [global_costmap.global_costmap]: Timed out waiting for transform from base_link to map to become available, tf error: Invalid frame ID "map" passed to canTransform argument target_frame - frame does not exist
[component_container_isolated-1] [INFO] [1722568881.226915503] [global_costmap.global_costmap]: Timed out waiting for transform from base_link to map to become available, tf error: Invalid frame ID "map" passed to canTransform argument target_frame - frame does not exist
[component_container_isolated-1] [INFO] [1722568881.726875434] [global_costmap.global_costmap]: Timed out waiting for transform from base_link to map to become available, tf error: Invalid frame ID "map" passed to canTransform argument target_frame - frame does not exist
[component_container_isolated-1] [WARN] [1722568881.838881998] [amcl]: AMCL cannot publish a pose or update the transform. Please set the initial pose...
[component_container_isolated-1] [INFO] [1722568882.226873001] [global_costmap.global_costmap]: Timed out waiting for transform from base_link to map to become available, tf error: Invalid frame ID "map" passed to canTransform argument target_frame - frame does not exist
[component_container_isolated-1] [INFO] [1722568882.726872037] [global_costmap.global_costmap]: Timed out waiting for transform from base_link to map to become available, tf error: Invalid frame ID "map" passed to canTransform argument target_frame - frame does not exist
[component_container_isolated-1] [INFO] [1722568883.226908063] [global_costmap.global_costmap]: Timed out waiting for transform from base_link to map to become available, tf error: Invalid frame ID "map" passed to canTransform argument target_frame - frame does not exist
[component_container_isolated-1] [INFO] [1722568883.726868821] [global_costmap.global_costmap]: Timed out waiting for transform from base_link to map to become available, tf error: Invalid frame ID "map" passed to canTransform argument target_frame - frame does not exist
[component_container_isolated-1] [WARN] [1722568883.936331382] [amcl]: AMCL cannot publish a pose or update the transform. Please set the initial pose...
[component_container_isolated-1] [INFO] [1722568884.226867550] [global_costmap.global_costmap]: Timed out waiting for transform from base_link to map to become available, tf error: Invalid frame ID "map" passed to canTransform argument target_frame - frame does not exist
[component_container_isolated-1] [INFO] [1722568884.726881766] [global_costmap.global_costmap]: Timed out waiting for transform from base_link to map to become available, tf error: Invalid frame ID "map" passed to canTransform argument target_frame - frame does not exist
[component_container_isolated-1] [INFO] [1722568885.226904815] [global_costmap.global_costmap]: Timed out waiting for transform from base_link to map to become available, tf error: Invalid frame ID "map" passed to canTransform argument target_frame - frame does not exist
[component_container_isolated-1] [INFO] [1722568885.726923232] [global_costmap.global_costmap]: Timed out waiting for transform from base_link to map to become available, tf error: Invalid frame ID "map" passed to canTransform argument target_frame - frame does not exist
[component_container_isolated-1] [WARN] [1722568886.034209349] [amcl]: AMCL cannot publish a pose or update the transform. Please set the initial pose...
[component_container_isolated-1] [INFO] [1722568886.226952052] [global_costmap.global_costmap]: Timed out waiting for transform from base_link to map to become available, tf error: Invalid frame ID "map" passed to canTransform argument target_frame - frame does not exist
[component_container_isolated-1] [INFO] [1722568886.726873063] [global_costmap.global_costmap]: Timed out waiting for transform from base_link to map to become available, tf error: Invalid frame ID "map" passed to canTransform argument target_frame - frame does not exist
[component_container_isolated-1] [INFO] [1722568887.226912146] [global_costmap.global_costmap]: Timed out waiting for transform from base_link to map to become available, tf error: Invalid frame ID "map" passed to canTransform argument target_frame - frame does not exist
[component_container_isolated-1] [INFO] [1722568887.726867929] [global_costmap.global_costmap]: Timed out waiting for transform from base_link to map to become available, tf error: Invalid frame ID "map" passed to canTransform argument target_frame - frame does not exist
[component_container_isolated-1] [WARN] [1722568888.082307176] [amcl]: AMCL cannot publish a pose or update the transform. Please set the initial pose...
[component_container_isolated-1] [INFO] [1722568888.226889447] [global_costmap.global_costmap]: Timed out waiting for transform from base_link to map to become available, tf error: Invalid frame ID "map" passed to canTransform argument target_frame - frame does not exist
[component_container_isolated-1] [INFO] [1722568888.726869033] [global_costmap.global_costmap]: Timed out waiting for transform from base_link to map to become available, tf error: Invalid frame ID "map" passed to canTransform argument target_frame - frame does not exist
[component_container_isolated-1] [INFO] [1722568889.226870877] [global_costmap.global_costmap]: Timed out waiting for transform from base_link to map to become available, tf error: Invalid frame ID "map" passed to canTransform argument target_frame - frame does not exist
[component_container_isolated-1] [INFO] [1722568889.726869859] [global_costmap.global_costmap]: Timed out waiting for transform from base_link to map to become available, tf error: Invalid frame ID "map" passed to canTransform argument target_frame - frame does not exist
[component_container_isolated-1] [WARN] [1722568890.180176449] [amcl]: AMCL cannot publish a pose or update the transform. Please set the initial pose...
[component_container_isolated-1] [INFO] [1722568890.226881606] [global_costmap.global_costmap]: Timed out waiting for transform from base_link to map to become available, tf error: Invalid frame ID "map" passed to canTransform argument target_frame - frame does not exist
[component_container_isolated-1] [INFO] [1722568890.726895992] [global_costmap.global_costmap]: Timed out waiting for transform from base_link to map to become available, tf error: Invalid frame ID "map" passed to canTransform argument target_frame - frame does not exist
[component_container_isolated-1] [INFO] [1722568891.226904915] [global_costmap.global_costmap]: Timed out waiting for transform from base_link to map to become available, tf error: Invalid frame ID "map" passed to canTransform argument target_frame - frame does not exist
[component_container_isolated-1] [INFO] [1722568891.726901827] [global_costmap.global_costmap]: Timed out waiting for transform from base_link to map to become available, tf error: Invalid frame ID "map" passed to canTransform argument target_frame - frame does not exist
[component_container_isolated-1] [INFO] [1722568892.226868302] [global_costmap.global_costmap]: Timed out waiting for transform from base_link to map to become available, tf error: Invalid frame ID "map" passed to canTransform argument target_frame - frame does not exist
[component_container_isolated-1] [WARN] [1722568892.278182169] [amcl]: AMCL cannot publish a pose or update the transform. Please set the initial pose...
[component_container_isolated-1] [INFO] [1722568892.726869380] [global_costmap.global_costmap]: Timed out waiting for transform from base_link to map to become available, tf error: Invalid frame ID "map" passed to canTransform argument target_frame - frame does not exist
[component_container_isolated-1] [INFO] [1722568893.226868921] [global_costmap.global_costmap]: Timed out waiting for transform from base_link to map to become available, tf error: Invalid frame ID "map" passed to canTransform argument target_frame - frame does not exist
[component_container_isolated-1] [INFO] [1722568893.726873954] [global_costmap.global_costmap]: Timed out waiting for transform from base_link to map to become available, tf error: Invalid frame ID "map" passed to canTransform argument target_frame - frame does not exist
[component_container_isolated-1] [INFO] [1722568894.226871786] [global_costmap.global_costmap]: Timed out waiting for transform from base_link to map to become available, tf error: Invalid frame ID "map" passed to canTransform argument target_frame - frame does not exist
[component_container_isolated-1] [WARN] [1722568894.326468739] [amcl]: AMCL cannot publish a pose or update the transform. Please set the initial pose...
[component_container_isolated-1] [INFO] [1722568894.726887408] [global_costmap.global_costmap]: Timed out waiting for transform from base_link to map to become available, tf error: Invalid frame ID "map" passed to canTransform argument target_frame - frame does not exist
[component_container_isolated-1] [INFO] [1722568895.226870734] [global_costmap.global_costmap]: Timed out waiting for transform from base_link to map to become available, tf error: Invalid frame ID "map" passed to canTransform argument target_frame - frame does not exist
[component_container_isolated-1] [INFO] [1722568895.726889475] [global_costmap.global_costmap]: Timed out waiting for transform from base_link to map to become available, tf error: Invalid frame ID "map" passed to canTransform argument target_frame - frame does not exist
[component_container_isolated-1] [INFO] [1722568896.226875931] [global_costmap.global_costmap]: Timed out waiting for transform from base_link to map to become available, tf error: Invalid frame ID "map" passed to canTransform argument target_frame - frame does not exist
[component_container_isolated-1] [WARN] [1722568896.378031728] [amcl]: AMCL cannot publish a pose or update the transform. Please set the initial pose...
[component_container_isolated-1] [INFO] [1722568896.726868133] [global_costmap.global_costmap]: Timed out waiting for transform from base_link to map to become available, tf error: Invalid frame ID "map" passed to canTransform argument target_frame - frame does not exist
[component_container_isolated-1] [INFO] [1722568897.226874094] [global_costmap.global_costmap]: Timed out waiting for transform from base_link to map to become available, tf error: Invalid frame ID "map" passed to canTransform argument target_frame - frame does not exist
[component_container_isolated-1] [INFO] [1722568897.726871648] [global_costmap.global_costmap]: Timed out waiting for transform from base_link to map to become available, tf error: Invalid frame ID "map" passed to canTransform argument target_frame - frame does not exist
[component_container_isolated-1] [INFO] [1722568898.226873357] [global_costmap.global_costmap]: Timed out waiting for transform from base_link to map to become available, tf error: Invalid frame ID "map" passed to canTransform argument target_frame - frame does not exist
[component_container_isolated-1] [WARN] [1722568898.476587898] [amcl]: AMCL cannot publish a pose or update the transform. Please set the initial pose...
[component_container_isolated-1] [INFO] [1722568898.726923996] [global_costmap.global_costmap]: Timed out waiting for transform from base_link to map to become available, tf error: Invalid frame ID "map" passed to canTransform argument target_frame - frame does not exist
[component_container_isolated-1] [INFO] [1722568899.226868050] [global_costmap.global_costmap]: Timed out waiting for transform from base_link to map to become available, tf error: Invalid frame ID "map" passed to canTransform argument target_frame - frame does not exist
[component_container_isolated-1] [INFO] [1722568899.726869569] [global_costmap.global_costmap]: Timed out waiting for transform from base_link to map to become available, tf error: Invalid frame ID "map" passed to canTransform argument target_frame - frame does not exist
[component_container_isolated-1] [INFO] [1722568900.226902693] [global_costmap.global_costmap]: Timed out waiting for transform from base_link to map to become available, tf error: Invalid frame ID "map" passed to canTransform argument target_frame - frame does not exist
[component_container_isolated-1] [WARN] [1722568900.571867388] [amcl]: AMCL cannot publish a pose or update the transform. Please set the initial pose...
[component_container_isolated-1] [INFO] [1722568900.726886485] [global_costmap.global_costmap]: Timed out waiting for transform from base_link to map to become available, tf error: Invalid frame ID "map" passed to canTransform argument target_frame - frame does not exist
[component_container_isolated-1] [INFO] [1722568901.226868651] [global_costmap.global_costmap]: Timed out waiting for transform from base_link to map to become available, tf error: Invalid frame ID "map" passed to canTransform argument target_frame - frame does not exist
[component_container_isolated-1] [INFO] [1722568901.726872335] [global_costmap.global_costmap]: Timed out waiting for transform from base_link to map to become available, tf error: Invalid frame ID "map" passed to canTransform argument target_frame - frame does not exist
[component_container_isolated-1] [INFO] [1722568902.226867978] [global_costmap.global_costmap]: Timed out waiting for transform from base_link to map to become available, tf error: Invalid frame ID "map" passed to canTransform argument target_frame - frame does not exist
[component_container_isolated-1] [WARN] [1722568902.624225450] [amcl]: AMCL cannot publish a pose or update the transform. Please set the initial pose...
[component_container_isolated-1] [INFO] [1722568902.726868894] [global_costmap.global_costmap]: Timed out waiting for transform from base_link to map to become available, tf error: Invalid frame ID "map" passed to canTransform argument target_frame - frame does not exist
[component_container_isolated-1] [INFO] [1722568903.226868618] [global_costmap.global_costmap]: Timed out waiting for transform from base_link to map to become available, tf error: Invalid frame ID "map" passed to canTransform argument target_frame - frame does not exist
[component_container_isolated-1] [INFO] [1722568903.726867177] [global_costmap.global_costmap]: Timed out waiting for transform from base_link to map to become available, tf error: Invalid frame ID "map" passed to canTransform argument target_frame - frame does not exist
[component_container_isolated-1] [INFO] [1722568904.226866750] [global_costmap.global_costmap]: Timed out waiting for transform from base_link to map to become available, tf error: Invalid frame ID "map" passed to canTransform argument target_frame - frame does not exist
[component_container_isolated-1] [WARN] [1722568904.722438143] [amcl]: AMCL cannot publish a pose or update the transform. Please set the initial pose...
[component_container_isolated-1] [INFO] [1722568904.726885255] [global_costmap.global_costmap]: Timed out waiting for transform from base_link to map to become available, tf error: Invalid frame ID "map" passed to canTransform argument target_frame - frame does not exist
[component_container_isolated-1] [INFO] [1722568905.226884260] [global_costmap.global_costmap]: Timed out waiting for transform from base_link to map to become available, tf error: Invalid frame ID "map" passed to canTransform argument target_frame - frame does not exist
[component_container_isolated-1] [INFO] [1722568905.726868344] [global_costmap.global_costmap]: Timed out waiting for transform from base_link to map to become available, tf error: Invalid frame ID "map" passed to canTransform argument target_frame - frame does not exist
[component_container_isolated-1] [INFO] [1722568906.226909952] [global_costmap.global_costmap]: Timed out waiting for transform from base_link to map to become available, tf error: Invalid frame ID "map" passed to canTransform argument target_frame - frame does not exist
[component_container_isolated-1] [INFO] [1722568906.726869855] [global_costmap.global_costmap]: Timed out waiting for transform from base_link to map to become available, tf error: Invalid frame ID "map" passed to canTransform argument target_frame - frame does not exist
[component_container_isolated-1] [WARN] [1722568906.818190893] [amcl]: AMCL cannot publish a pose or update the transform. Please set the initial pose...
[component_container_isolated-1] [INFO] [1722568907.226868639] [global_costmap.global_costmap]: Timed out waiting for transform from base_link to map to become available, tf error: Invalid frame ID "map" passed to canTransform argument target_frame - frame does not exist
[component_container_isolated-1] [INFO] [1722568907.726929170] [global_costmap.global_costmap]: Timed out waiting for transform from base_link to map to become available, tf error: Invalid frame ID "map" passed to canTransform argument target_frame - frame does not exist
[component_container_isolated-1] [INFO] [1722568908.226921636] [global_costmap.global_costmap]: Timed out waiting for transform from base_link to map to become available, tf error: Invalid frame ID "map" passed to canTransform argument target_frame - frame does not exist
[component_container_isolated-1] [INFO] [1722568908.726868727] [global_costmap.global_costmap]: Timed out waiting for transform from base_link to map to become available, tf error: Invalid frame ID "map" passed to canTransform argument target_frame - frame does not exist
[component_container_isolated-1] [WARN] [1722568908.870183896] [amcl]: AMCL cannot publish a pose or update the transform. Please set the initial pose...
[component_container_isolated-1] [INFO] [1722568909.226874578] [global_costmap.global_costmap]: Timed out waiting for transform from base_link to map to become available, tf error: Invalid frame ID "map" passed to canTransform argument target_frame - frame does not exist
[component_container_isolated-1] [INFO] [1722568909.726867653] [global_costmap.global_costmap]: Timed out waiting for transform from base_link to map to become available, tf error: Invalid frame ID "map" passed to canTransform argument target_frame - frame does not exist
[component_container_isolated-1] [INFO] [1722568910.226879151] [global_costmap.global_costmap]: Timed out waiting for transform from base_link to map to become available, tf error: Invalid frame ID "map" passed to canTransform argument target_frame - frame does not exist
[component_container_isolated-1] [INFO] [1722568910.726867737] [global_costmap.global_costmap]: Timed out waiting for transform from base_link to map to become available, tf error: Invalid frame ID "map" passed to canTransform argument target_frame - frame does not exist
[component_container_isolated-1] [WARN] [1722568910.969269552] [amcl]: AMCL cannot publish a pose or update the transform. Please set the initial pose...
[component_container_isolated-1] [INFO] [1722568911.226939751] [global_costmap.global_costmap]: Timed out waiting for transform from base_link to map to become available, tf error: Invalid frame ID "map" passed to canTransform argument target_frame - frame does not exist
[component_container_isolated-1] [INFO] [1722568911.726869281] [global_costmap.global_costmap]: Timed out waiting for transform from base_link to map to become available, tf error: Invalid frame ID "map" passed to canTransform argument target_frame - frame does not exist
[component_container_isolated-1] [INFO] [1722568912.226884416] [global_costmap.global_costmap]: Timed out waiting for transform from base_link to map to become available, tf error: Invalid frame ID "map" passed to canTransform argument target_frame - frame does not exist
[component_container_isolated-1] [INFO] [1722568912.726869229] [global_costmap.global_costmap]: Timed out waiting for transform from base_link to map to become available, tf error: Invalid frame ID "map" passed to canTransform argument target_frame - frame does not exist
[component_container_isolated-1] [WARN] [1722568913.067959140] [amcl]: AMCL cannot publish a pose or update the transform. Please set the initial pose...
[component_container_isolated-1] [INFO] [1722568913.226870904] [global_costmap.global_costmap]: Timed out waiting for transform from base_link to map to become available, tf error: Invalid frame ID "map" passed to canTransform argument target_frame - frame does not exist
[component_container_isolated-1] [INFO] [1722568913.726872398] [global_costmap.global_costmap]: Timed out waiting for transform from base_link to map to become available, tf error: Invalid frame ID "map" passed to canTransform argument target_frame - frame does not exist
[component_container_isolated-1] [INFO] [1722568914.226871051] [global_costmap.global_costmap]: Timed out waiting for transform from base_link to map to become available, tf error: Invalid frame ID "map" passed to canTransform argument target_frame - frame does not exist
[component_container_isolated-1] [INFO] [1722568914.726885011] [global_costmap.global_costmap]: Timed out waiting for transform from base_link to map to become available, tf error: Invalid frame ID "map" passed to canTransform argument target_frame - frame does not exist
[component_container_isolated-1] [WARN] [1722568915.117101952] [amcl]: AMCL cannot publish a pose or update the transform. Please set the initial pose...
[component_container_isolated-1] [INFO] [1722568915.226908130] [global_costmap.global_costmap]: Timed out waiting for transform from base_link to map to become available, tf error: Invalid frame ID "map" passed to canTransform argument target_frame - frame does not exist
[component_container_isolated-1] [INFO] [1722568915.726880869] [global_costmap.global_costmap]: Timed out waiting for transform from base_link to map to become available, tf error: Invalid frame ID "map" passed to canTransform argument target_frame - frame does not exist
[component_container_isolated-1] [INFO] [1722568916.226867180] [global_costmap.global_costmap]: Timed out waiting for transform from base_link to map to become available, tf error: Invalid frame ID "map" passed to canTransform argument target_frame - frame does not exist
[component_container_isolated-1] [INFO] [1722568916.726870731] [global_costmap.global_costmap]: Timed out waiting for transform from base_link to map to become available, tf error: Invalid frame ID "map" passed to canTransform argument target_frame - frame does not exist
[component_container_isolated-1] [WARN] [1722568917.216213976] [amcl]: AMCL cannot publish a pose or update the transform. Please set the initial pose...
[component_container_isolated-1] [INFO] [1722568917.226998871] [global_costmap.global_costmap]: Timed out waiting for transform from base_link to map to become available, tf error: Invalid frame ID "map" passed to canTransform argument target_frame - frame does not exist
[component_container_isolated-1] [INFO] [1722568917.726882373] [global_costmap.global_costmap]: Timed out waiting for transform from base_link to map to become available, tf error: Invalid frame ID "map" passed to canTransform argument target_frame - frame does not exist
[component_container_isolated-1] [INFO] [1722568918.226877377] [global_costmap.global_costmap]: Timed out waiting for transform from base_link to map to become available, tf error: Invalid frame ID "map" passed to canTransform argument target_frame - frame does not exist
[component_container_isolated-1] [INFO] [1722568918.726863276] [global_costmap.global_costmap]: Timed out waiting for transform from base_link to map to become available, tf error: Invalid frame ID "map" passed to canTransform argument target_frame - frame does not exist
[component_container_isolated-1] [INFO] [1722568919.226891272] [global_costmap.global_costmap]: Timed out waiting for transform from base_link to map to become available, tf error: Invalid frame ID "map" passed to canTransform argument target_frame - frame does not exist
[component_container_isolated-1] [WARN] [1722568919.315410756] [amcl]: AMCL cannot publish a pose or update the transform. Please set the initial pose...
[component_container_isolated-1] [INFO] [1722568919.726870074] [global_costmap.global_costmap]: Timed out waiting for transform from base_link to map to become available, tf error: Invalid frame ID "map" passed to canTransform argument target_frame - frame does not exist
[component_container_isolated-1] [INFO] [1722568920.226869651] [global_costmap.global_costmap]: Timed out waiting for transform from base_link to map to become available, tf error: Invalid frame ID "map" passed to canTransform argument target_frame - frame does not exist
[component_container_isolated-1] [INFO] [1722568920.726887764] [global_costmap.global_costmap]: Timed out waiting for transform from base_link to map to become available, tf error: Invalid frame ID "map" passed to canTransform argument target_frame - frame does not exist
[component_container_isolated-1] [INFO] [1722568921.226918895] [global_costmap.global_costmap]: Timed out waiting for transform from base_link to map to become available, tf error: Invalid frame ID "map" passed to canTransform argument target_frame - frame does not exist
[component_container_isolated-1] [WARN] [1722568921.415757945] [amcl]: AMCL cannot publish a pose or update the transform. Please set the initial pose...
[component_container_isolated-1] [INFO] [1722568921.726871497] [global_costmap.global_costmap]: Timed out waiting for transform from base_link to map to become available, tf error: Invalid frame ID "map" passed to canTransform argument target_frame - frame does not exist
[component_container_isolated-1] [INFO] [1722568922.226871306] [global_costmap.global_costmap]: Timed out waiting for transform from base_link to map to become available, tf error: Invalid frame ID "map" passed to canTransform argument target_frame - frame does not exist
[component_container_isolated-1] [INFO] [1722568922.726871935] [global_costmap.global_costmap]: Timed out waiting for transform from base_link to map to become available, tf error: Invalid frame ID "map" passed to canTransform argument target_frame - frame does not exist
[component_container_isolated-1] [INFO] [1722568923.226873613] [global_costmap.global_costmap]: Timed out waiting for transform from base_link to map to become available, tf error: Invalid frame ID "map" passed to canTransform argument target_frame - frame does not exist
[component_container_isolated-1] [WARN] [1722568923.464158675] [amcl]: AMCL cannot publish a pose or update the transform. Please set the initial pose...
[component_container_isolated-1] [INFO] [1722568923.726904759] [global_costmap.global_costmap]: Timed out waiting for transform from base_link to map to become available, tf error: Invalid frame ID "map" passed to canTransform argument target_frame - frame does not exist
[component_container_isolated-1] [INFO] [1722568924.226898432] [global_costmap.global_costmap]: Timed out waiting for transform from base_link to map to become available, tf error: Invalid frame ID "map" passed to canTransform argument target_frame - frame does not exist
[component_container_isolated-1] [INFO] [1722568924.726870695] [global_costmap.global_costmap]: Timed out waiting for transform from base_link to map to become available, tf error: Invalid frame ID "map" passed to canTransform argument target_frame - frame does not exist
[component_container_isolated-1] [INFO] [1722568925.226952317] [global_costmap.global_costmap]: Timed out waiting for transform from base_link to map to become available, tf error: Invalid frame ID "map" passed to canTransform argument target_frame - frame does not exist
[component_container_isolated-1] [WARN] [1722568925.563091125] [amcl]: AMCL cannot publish a pose or update the transform. Please set the initial pose...
[component_container_isolated-1] [INFO] [1722568925.726869672] [global_costmap.global_costmap]: Timed out waiting for transform from base_link to map to become available, tf error: Invalid frame ID "map" passed to canTransform argument target_frame - frame does not exist
[component_container_isolated-1] [INFO] [1722568926.226884134] [global_costmap.global_costmap]: Timed out waiting for transform from base_link to map to become available, tf error: Invalid frame ID "map" passed to canTransform argument target_frame - frame does not exist
[component_container_isolated-1] [INFO] [1722568926.726918195] [global_costmap.global_costmap]: Timed out waiting for transform from base_link to map to become available, tf error: Invalid frame ID "map" passed to canTransform argument target_frame - frame does not exist
[component_container_isolated-1] [INFO] [1722568927.226935437] [global_costmap.global_costmap]: Timed out waiting for transform from base_link to map to become available, tf error: Invalid frame ID "map" passed to canTransform argument target_frame - frame does not exist
[component_container_isolated-1] [WARN] [1722568927.661275218] [amcl]: AMCL cannot publish a pose or update the transform. Please set the initial pose...
[component_container_isolated-1] [INFO] [1722568927.726890419] [global_costmap.global_costmap]: Timed out waiting for transform from base_link to map to become available, tf error: Invalid frame ID "map" passed to canTransform argument target_frame - frame does not exist
[component_container_isolated-1] [INFO] [1722568928.226903063] [global_costmap.global_costmap]: Timed out waiting for transform from base_link to map to become available, tf error: Invalid frame ID "map" passed to canTransform argument target_frame - frame does not exist
[component_container_isolated-1] [INFO] [1722568928.726895839] [global_costmap.global_costmap]: Timed out waiting for transform from base_link to map to become available, tf error: Invalid frame ID "map" passed to canTransform argument target_frame - frame does not exist
[component_container_isolated-1] [INFO] [1722568929.226938895] [global_costmap.global_costmap]: Timed out waiting for transform from base_link to map to become available, tf error: Invalid frame ID "map" passed to canTransform argument target_frame - frame does not exist
[component_container_isolated-1] [WARN] [1722568929.709626102] [amcl]: AMCL cannot publish a pose or update the transform. Please set the initial pose...
[component_container_isolated-1] [INFO] [1722568929.726881731] [global_costmap.global_costmap]: Timed out waiting for transform from base_link to map to become available, tf error: Invalid frame ID "map" passed to canTransform argument target_frame - frame does not exist
[component_container_isolated-1] [ERROR] [1722568929.726925554] [global_costmap.global_costmap]: Failed to activate global_costmap because transform from base_link to map did not become available before timeout
[component_container_isolated-1] [ERROR] [1722568929.727303978] [lifecycle_manager_navigation]: Failed to change state for node: planner_server
[component_container_isolated-1] [ERROR] [1722568929.727326440] [lifecycle_manager_navigation]: Failed to bring up all requested nodes. Aborting bringup.
[component_container_isolated-1] [WARN] [1722568931.807923473] [amcl]: AMCL cannot publish a pose or update the transform. Please set the initial pose...
[component_container_isolated-1] [WARN] [1722568933.906278299] [amcl]: AMCL cannot publish a pose or update the transform. Please set the initial pose...
[component_container_isolated-1] [WARN] [1722568935.955340807] [amcl]: AMCL cannot publish a pose or update the transform. Please set the initial pose...
[component_container_isolated-1] [WARN] [1722568938.053232216] [amcl]: AMCL cannot publish a pose or update the transform. Please set the initial pose...
[component_container_isolated-1] [WARN] [1722568940.151821625] [amcl]: AMCL cannot publish a pose or update the transform. Please set the initial pose...
[component_container_isolated-1] [WARN] [1722568942.198193911] [amcl]: AMCL cannot publish a pose or update the transform. Please set the initial pose...
[component_container_isolated-1] [WARN] [1722568944.199508955] [amcl]: AMCL cannot publish a pose or update the transform. Please set the initial pose...

Here is the ROS graph at this time: rosgraph_1

Since the map coordinate frame cannot be selected in rviz2's Fixes Frame, I cannot set the initial pose at this time. It can be seen that scan has data. What puzzles me is that the map cannot be displayed inrviz2 at this time. However, as can be seen from the log file, the map information has already been read. Below is map.yaml:

image: map.pgm
mode: trinary
resolution: 0.05
origin: [-10, -10, 0]
negate: 0
occupied_thresh: 0.65
free_thresh: 0.25

截图 2024-08-02 11-26-21 When I check the TF tree, I find that there is still no transformation relationship from map->odom.

frames ​ I think it might be that my amcl is not correctly publishing the map->odom coordinate transformation. Could it be that the selection of coordinate frames in my configuration file has some issues? I am a bit confused about whether the configuration file should include the/.

​ The above is a more detailed description of my problem. I would be honored if you could reply to me again. Thank you once again!

SteveMacenski commented 1 month ago

[component_container_isolated-1] [INFO] [1722568867.496972710] [amcl]: Received a 384 X 384 map @ 0.050 m/pix

You have a map :+1:

You're getting laser scan data :+1:

[component_container_isolated-1] [WARN] [1722568869.460232746] [amcl]: AMCL cannot publish a pose or update the transform. Please set the initial pose...

This is your issue. You need to set the initial pose for AMCL to use. Then it'll start publishing. Otherwise, it has no idea where it starts and would just publish a garbage initial transformation. This can be done for testing in rviz using the default "2D pose estimate" tool, or via a publisher to the /initialpose topic (or from parameters, or global localization service to have it try to 'guess' where it is with some motion).

This is all covered in our getting started tutorial https://docs.nav2.org/getting_started/index.html

SteveMacenski commented 1 month ago

Closing - I believe this is the clear answer given the logs and there hasn't been a response in a week. Happy to engage still if there's anything more.