ros-navigation / navigation2

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

Add namespace for planner_server node, global_costmap will not work properly with tf error #3054

Closed RayOwwen closed 2 years ago

RayOwwen commented 2 years ago

Bug report

Required Info:

Steps to reproduce issue

1.Modify tb3_simulation_launch.py, don't use composition.

    declare_use_composition_cmd = DeclareLaunchArgument(
        'use_composition', default_value='False',
        description='Whether to use composed bringup')

2.Modify navigation_launch.py,for adding namespace to planner_server node.

    lifecycle_nodes = ['controller_server',
                       'smoother_server',
                       'dynamic/planner_server',
                       'behavior_server',
                       'bt_navigator',
                       'waypoint_follower']

            Node(
                package='nav2_planner',
                executable='planner_server',
                name='planner_server',
                namespace='dynamic',
                output='screen',
                respawn=use_respawn,
                respawn_delay=2.0,
                parameters=[configured_params],
                remappings=remappings),
  1. Start simulation
    ros2 launch nav2_bringup tb3_simulation_launch.py headless:=False

    Expected behavior

    My target is to start two planner_server node in different namespace. The two planner_server have different global_costmap parameters, one without obstacle layer, so I can computer path in different global_costmap.

    Actual behavior

    When I add namespace to planner_server node, and the global_costmap cannot work properly, with tf error.

    Additional information

    $ ros2 launch nav2_bringup tb3_simulation_launch.py headless:=False
    [INFO] [launch]: All log files can be found below /home/owen/.ros/log/2022-07-01-17-15-33-725707-owen-G5-5500-28421
    [INFO] [launch]: Default logging verbosity is set to INFO
    [INFO] [gzserver-1]: process started with pid [28422]
    [INFO] [gzclient-2]: process started with pid [28424]
    [INFO] [spawn_entity.py-3]: process started with pid [28426]
    [INFO] [robot_state_publisher-4]: process started with pid [28428]
    [INFO] [rviz2-5]: process started with pid [28430]
    [INFO] [map_server-6]: process started with pid [28432]
    [INFO] [amcl-7]: process started with pid [28434]
    [INFO] [lifecycle_manager-8]: process started with pid [28436]
    [INFO] [controller_server-9]: process started with pid [28438]
    [INFO] [smoother_server-10]: process started with pid [28440]
    [INFO] [planner_server-11]: process started with pid [28442]
    [INFO] [behavior_server-12]: process started with pid [28444]
    [INFO] [bt_navigator-13]: process started with pid [28456]
    [INFO] [waypoint_follower-14]: process started with pid [28498]
    [INFO] [lifecycle_manager-15]: process started with pid [28505]
    [robot_state_publisher-4] Link base_link had 7 children
    [robot_state_publisher-4] Link camera_link had 2 children
    [robot_state_publisher-4] Link camera_depth_frame had 1 children
    [robot_state_publisher-4] Link camera_depth_optical_frame had 0 children
    [robot_state_publisher-4] Link camera_rgb_frame had 1 children
    [robot_state_publisher-4] Link camera_rgb_optical_frame had 0 children
    [robot_state_publisher-4] Link caster_back_left_link had 0 children
    [robot_state_publisher-4] Link caster_back_right_link had 0 children
    [robot_state_publisher-4] Link imu_link had 0 children
    [robot_state_publisher-4] Link base_scan had 0 children
    [robot_state_publisher-4] Link wheel_left_link had 0 children
    [robot_state_publisher-4] Link wheel_right_link had 0 children
    [robot_state_publisher-4] [INFO] [1656666934.697340395] [robot_state_publisher]: got segment base_footprint
    [robot_state_publisher-4] [INFO] [1656666934.697974571] [robot_state_publisher]: got segment base_link
    [robot_state_publisher-4] [INFO] [1656666934.698497975] [robot_state_publisher]: got segment base_scan
    [robot_state_publisher-4] [INFO] [1656666934.699007301] [robot_state_publisher]: got segment camera_depth_frame
    [robot_state_publisher-4] [INFO] [1656666934.699523440] [robot_state_publisher]: got segment camera_depth_optical_frame
    [robot_state_publisher-4] [INFO] [1656666934.700015154] [robot_state_publisher]: got segment camera_link
    [robot_state_publisher-4] [INFO] [1656666934.700523133] [robot_state_publisher]: got segment camera_rgb_frame
    [robot_state_publisher-4] [INFO] [1656666934.701051075] [robot_state_publisher]: got segment camera_rgb_optical_frame
    [robot_state_publisher-4] [INFO] [1656666934.701066901] [robot_state_publisher]: got segment caster_back_left_link
    [robot_state_publisher-4] [INFO] [1656666934.701075453] [robot_state_publisher]: got segment caster_back_right_link
    [robot_state_publisher-4] [INFO] [1656666934.701083248] [robot_state_publisher]: got segment imu_link
    [robot_state_publisher-4] [INFO] [1656666934.701090942] [robot_state_publisher]: got segment wheel_left_link
    [robot_state_publisher-4] [INFO] [1656666934.701098863] [robot_state_publisher]: got segment wheel_right_link
    [waypoint_follower-14] [INFO] [1656666934.710707880] [waypoint_follower]: 
    [waypoint_follower-14]  waypoint_follower lifecycle node launched. 
    [waypoint_follower-14]  Waiting on external lifecycle transitions to activate
    [waypoint_follower-14]  See https://design.ros2.org/articles/node_lifecycle.html for more information.
    [lifecycle_manager-8] [INFO] [1656666934.729357796] [lifecycle_manager_localization]: Creating and initializing lifecycle service clients
    [amcl-7] [INFO] [1656666934.736594603] [amcl]: 
    [amcl-7]    amcl lifecycle node launched. 
    [amcl-7]    Waiting on external lifecycle transitions to activate
    [amcl-7]    See https://design.ros2.org/articles/node_lifecycle.html for more information.
    [behavior_server-12] [INFO] [1656666934.738129674] [behavior_server]: 
    [behavior_server-12]    behavior_server lifecycle node launched. 
    [behavior_server-12]    Waiting on external lifecycle transitions to activate
    [behavior_server-12]    See https://design.ros2.org/articles/node_lifecycle.html for more information.
    [bt_navigator-13] [INFO] [1656666934.757507422] [bt_navigator]: 
    [bt_navigator-13]   bt_navigator lifecycle node launched. 
    [bt_navigator-13]   Waiting on external lifecycle transitions to activate
    [bt_navigator-13]   See https://design.ros2.org/articles/node_lifecycle.html for more information.
    [lifecycle_manager-15] [INFO] [1656666934.761272218] [lifecycle_manager_navigation]: Creating and initializing lifecycle service clients
    [map_server-6] [INFO] [1656666934.776173183] [map_server]: 
    [map_server-6]  map_server lifecycle node launched. 
    [map_server-6]  Waiting on external lifecycle transitions to activate
    [map_server-6]  See https://design.ros2.org/articles/node_lifecycle.html for more information.
    [controller_server-9] [INFO] [1656666934.804378397] [controller_server]: 
    [controller_server-9]   controller_server lifecycle node launched. 
    [controller_server-9]   Waiting on external lifecycle transitions to activate
    [controller_server-9]   See https://design.ros2.org/articles/node_lifecycle.html for more information.
    [controller_server-9] [INFO] [1656666934.811222256] [controller_server]: Creating controller server
    [smoother_server-10] [INFO] [1656666934.828472966] [smoother_server]: 
    [smoother_server-10]    smoother_server lifecycle node launched. 
    [smoother_server-10]    Waiting on external lifecycle transitions to activate
    [smoother_server-10]    See https://design.ros2.org/articles/node_lifecycle.html for more information.
    [planner_server-11] [INFO] [1656666934.828700720] [dynamic.planner_server]: 
    [planner_server-11]     planner_server lifecycle node launched. 
    [planner_server-11]     Waiting on external lifecycle transitions to activate
    [planner_server-11]     See https://design.ros2.org/articles/node_lifecycle.html for more information.
    [smoother_server-10] [INFO] [1656666934.831585415] [smoother_server]: Creating smoother server
    [lifecycle_manager-8] [INFO] [1656666934.850907625] [lifecycle_manager_localization]: Starting managed nodes bringup...
    [lifecycle_manager-8] [INFO] [1656666934.850970452] [lifecycle_manager_localization]: Configuring map_server
    [map_server-6] [INFO] [map_io]: Loading yaml file: /home/owen/nav2_humble_ws/install/nav2_bringup/share/nav2_bringup/maps/turtlebot3_world.yaml
    [map_server-6] [DEBUG] [map_io]: resolution: 0.05
    [map_server-6] [DEBUG] [map_io]: free_thresh: 0.196
    [map_server-6] [DEBUG] [map_io]: occupied_thresh: 0.65
    [map_server-6] [DEBUG] [map_io]: mode: trinary
    [map_server-6] [DEBUG] [map_io]: negate: 0
    [map_server-6] [INFO] [map_io]: Loading image_file: /home/owen/nav2_humble_ws/install/nav2_bringup/share/nav2_bringup/maps/turtlebot3_world.pgm
    [controller_server-9] [INFO] [1656666934.855400300] [local_costmap.local_costmap]: 
    [controller_server-9]   local_costmap lifecycle node launched. 
    [controller_server-9]   Waiting on external lifecycle transitions to activate
    [controller_server-9]   See https://design.ros2.org/articles/node_lifecycle.html for more information.
    [controller_server-9] [INFO] [1656666934.856605749] [local_costmap.local_costmap]: Creating Costmap
    [planner_server-11] [INFO] [1656666934.872881148] [dynamic.global_costmap.global_costmap]: 
    [planner_server-11]     global_costmap lifecycle node launched. 
    [planner_server-11]     Waiting on external lifecycle transitions to activate
    [planner_server-11]     See https://design.ros2.org/articles/node_lifecycle.html for more information.
    [planner_server-11] [INFO] [1656666934.874034745] [dynamic.global_costmap.global_costmap]: Creating Costmap
    [map_server-6] [DEBUG] [map_io]: Read map /home/owen/nav2_humble_ws/install/nav2_bringup/share/nav2_bringup/maps/turtlebot3_world.pgm: 384 X 384 map @ 0.05 m/cell
    [lifecycle_manager-8] [INFO] [1656666934.940659247] [lifecycle_manager_localization]: Configuring amcl
    [lifecycle_manager-15] [INFO] [1656666934.951992170] [lifecycle_manager_navigation]: Starting managed nodes bringup...
    [lifecycle_manager-15] [INFO] [1656666934.952040593] [lifecycle_manager_navigation]: Configuring controller_server
    [controller_server-9] [INFO] [1656666934.952514122] [controller_server]: Configuring controller interface
    [controller_server-9] [INFO] [1656666934.952711836] [controller_server]: getting goal checker plugins..
    [controller_server-9] [INFO] [1656666934.952853314] [controller_server]: Controller frequency set to 20.0000Hz
    [controller_server-9] [INFO] [1656666934.959875127] [local_costmap.local_costmap]: Using plugin "voxel_layer"
    [amcl-7] [INFO] [1656666934.959916983] [amcl]: Subscribed to map topic.
    [lifecycle_manager-8] [INFO] [1656666934.965363221] [lifecycle_manager_localization]: Activating map_server
    [map_server-6] [INFO] [1656666934.965904271] [map_server]: Creating bond (map_server) to lifecycle manager.
    [amcl-7] [INFO] [1656666934.966319655] [amcl]: Received a 384 X 384 map @ 0.050 m/pix
    [controller_server-9] [INFO] [1656666934.968429746] [local_costmap.local_costmap]: Subscribed to Topics: scan
    [controller_server-9] [INFO] [1656666934.986627017] [local_costmap.local_costmap]: Initialized plugin "voxel_layer"
    [controller_server-9] [INFO] [1656666934.986658713] [local_costmap.local_costmap]: Using plugin "inflation_layer"
    [controller_server-9] [INFO] [1656666934.988482569] [local_costmap.local_costmap]: Initialized plugin "inflation_layer"
    [controller_server-9] [INFO] [1656666935.000012005] [controller_server]: Created progress_checker : progress_checker of type nav2_controller::SimpleProgressChecker
    [controller_server-9] [INFO] [1656666935.001009898] [controller_server]: Created goal checker : general_goal_checker of type nav2_controller::SimpleGoalChecker
    [controller_server-9] [INFO] [1656666935.001553414] [controller_server]: Controller Server has general_goal_checker  goal checkers available.
    [controller_server-9] [INFO] [1656666935.004581981] [controller_server]: Created controller : FollowPath of type dwb_core::DWBLocalPlanner
    [controller_server-9] [INFO] [1656666935.005856218] [controller_server]: Setting transform_tolerance to 0.200000
    [controller_server-9] [INFO] [1656666935.017739095] [controller_server]: Using critic "RotateToGoal" (dwb_critics::RotateToGoalCritic)
    [controller_server-9] [INFO] [1656666935.018473928] [controller_server]: Critic plugin initialized
    [controller_server-9] [INFO] [1656666935.018684508] [controller_server]: Using critic "Oscillation" (dwb_critics::OscillationCritic)
    [controller_server-9] [INFO] [1656666935.019368466] [controller_server]: Critic plugin initialized
    [controller_server-9] [INFO] [1656666935.019571827] [controller_server]: Using critic "BaseObstacle" (dwb_critics::BaseObstacleCritic)
    [controller_server-9] [INFO] [1656666935.019897556] [controller_server]: Critic plugin initialized
    [controller_server-9] [INFO] [1656666935.020098793] [controller_server]: Using critic "GoalAlign" (dwb_critics::GoalAlignCritic)
    [controller_server-9] [INFO] [1656666935.020772026] [controller_server]: Critic plugin initialized
    [controller_server-9] [INFO] [1656666935.021023204] [controller_server]: Using critic "PathAlign" (dwb_critics::PathAlignCritic)
    [controller_server-9] [INFO] [1656666935.021528784] [controller_server]: Critic plugin initialized
    [controller_server-9] [INFO] [1656666935.021747285] [controller_server]: Using critic "PathDist" (dwb_critics::PathDistCritic)
    [controller_server-9] [INFO] [1656666935.022114460] [controller_server]: Critic plugin initialized
    [controller_server-9] [INFO] [1656666935.022317421] [controller_server]: Using critic "GoalDist" (dwb_critics::GoalDistCritic)
    [controller_server-9] [INFO] [1656666935.022806783] [controller_server]: Critic plugin initialized
    [controller_server-9] [INFO] [1656666935.022911358] [controller_server]: Controller Server has FollowPath  controllers available.
    [lifecycle_manager-15] [INFO] [1656666935.068258129] [lifecycle_manager_navigation]: Configuring smoother_server
    [smoother_server-10] [INFO] [1656666935.068491205] [smoother_server]: Configuring smoother server
    [lifecycle_manager-8] [INFO] [1656666935.075679929] [lifecycle_manager_localization]: Server map_server connected with bond.
    [lifecycle_manager-8] [INFO] [1656666935.075736539] [lifecycle_manager_localization]: Activating amcl
    [amcl-7] [INFO] [1656666935.076056022] [amcl]: Creating bond (amcl) to lifecycle manager.
    [smoother_server-10] [INFO] [1656666935.079795458] [smoother_server]: Created smoother : simple_smoother of type nav2_smoother::SimpleSmoother
    [smoother_server-10] [INFO] [1656666935.081424856] [smoother_server]: Smoother Server has simple_smoother  smoothers available.
    [lifecycle_manager-15] [INFO] [1656666935.090481537] [lifecycle_manager_navigation]: Configuring dynamic/planner_server
    [planner_server-11] [INFO] [1656666935.097754561] [dynamic.global_costmap.global_costmap]: Using plugin "static_layer"
    [planner_server-11] [INFO] [1656666935.104258018] [dynamic.global_costmap.global_costmap]: Subscribing to the map topic (/dynamic/map) with transient local durability
    [planner_server-11] [INFO] [1656666935.106885744] [dynamic.global_costmap.global_costmap]: Initialized plugin "static_layer"
    [planner_server-11] [INFO] [1656666935.106920497] [dynamic.global_costmap.global_costmap]: Using plugin "obstacle_layer"
    [planner_server-11] [INFO] [1656666935.108053150] [dynamic.global_costmap.global_costmap]: Subscribed to Topics: 
    [planner_server-11] [INFO] [1656666935.108113155] [dynamic.global_costmap.global_costmap]: Initialized plugin "obstacle_layer"
    [planner_server-11] [INFO] [1656666935.108122786] [dynamic.global_costmap.global_costmap]: Using plugin "inflation_layer"
    [planner_server-11] [INFO] [1656666935.109574044] [dynamic.global_costmap.global_costmap]: Initialized plugin "inflation_layer"
    [spawn_entity.py-3] [INFO] [1656666935.113190211] [spawn_entity]: Spawn Entity started
    [spawn_entity.py-3] [INFO] [1656666935.113581563] [spawn_entity]: Loading entity XML from file /home/owen/nav2_humble_ws/install/nav2_bringup/share/nav2_bringup/worlds/waffle.model
    [spawn_entity.py-3] [INFO] [1656666935.114382705] [spawn_entity]: Waiting for service /spawn_entity, timeout = 30
    [spawn_entity.py-3] [INFO] [1656666935.114778226] [spawn_entity]: Waiting for service /spawn_entity
    [planner_server-11] [INFO] [1656666935.122986018] [dynamic.planner_server]: Created global planner plugin GridBased of type nav2_navfn_planner/NavfnPlanner
    [planner_server-11] [INFO] [1656666935.123040933] [dynamic.planner_server]: Configuring plugin GridBased of type NavfnPlanner
    [planner_server-11] [INFO] [1656666935.123807928] [dynamic.planner_server]: Planner Server has GridBased  planners available.
    [lifecycle_manager-15] [INFO] [1656666935.135871327] [lifecycle_manager_navigation]: Configuring behavior_server
    [behavior_server-12] [INFO] [1656666935.145525222] [behavior_server]: Creating behavior plugin spin of type nav2_behaviors/Spin
    [behavior_server-12] [INFO] [1656666935.147104592] [behavior_server]: Configuring spin
    [behavior_server-12] [INFO] [1656666935.153790785] [behavior_server]: Creating behavior plugin backup of type nav2_behaviors/BackUp
    [behavior_server-12] [INFO] [1656666935.154963124] [behavior_server]: Configuring backup
    [behavior_server-12] [INFO] [1656666935.159432841] [behavior_server]: Creating behavior plugin drive_on_heading of type nav2_behaviors/DriveOnHeading
    [behavior_server-12] [INFO] [1656666935.160572040] [behavior_server]: Configuring drive_on_heading
    [behavior_server-12] [INFO] [1656666935.165402768] [behavior_server]: Creating behavior plugin wait of type nav2_behaviors/Wait
    [behavior_server-12] [INFO] [1656666935.166565872] [behavior_server]: Configuring wait
    [lifecycle_manager-15] [INFO] [1656666935.172129715] [lifecycle_manager_navigation]: Configuring bt_navigator
    [lifecycle_manager-8] [INFO] [1656666935.182087417] [lifecycle_manager_localization]: Server amcl connected with bond.
    [lifecycle_manager-8] [INFO] [1656666935.182128964] [lifecycle_manager_localization]: Managed nodes are active
    [lifecycle_manager-8] [INFO] [1656666935.182143673] [lifecycle_manager_localization]: Creating bond timer...
    [lifecycle_manager-15] [INFO] [1656666935.344945735] [lifecycle_manager_navigation]: Configuring waypoint_follower
    [waypoint_follower-14] [INFO] [1656666935.356144602] [waypoint_follower]: Created waypoint_task_executor : wait_at_waypoint of type nav2_waypoint_follower::WaitAtWaypoint
    [lifecycle_manager-15] [INFO] [1656666935.357087524] [lifecycle_manager_navigation]: Activating controller_server
    [controller_server-9] [INFO] [1656666935.357317233] [local_costmap.local_costmap]: Checking transform
    [controller_server-9] [INFO] [1656666935.357353108] [local_costmap.local_costmap]: Timed out waiting for transform from base_link to odom to become available, tf error: Invalid frame ID "odom" passed to canTransform argument target_frame - frame does not exist
    [rviz2-5] [INFO] [1656666935.651630133] [rviz2]: Stereo is NOT SUPPORTED
    [rviz2-5] [INFO] [1656666935.651817129] [rviz2]: OpenGl version: 4.6 (GLSL 4.6)
    [rviz2-5] [INFO] [1656666935.752643944] [rviz2]: Stereo is NOT SUPPORTED
    [controller_server-9] [INFO] [1656666935.857425751] [local_costmap.local_costmap]: Timed out waiting for transform from base_link to odom to become available, tf error: Invalid frame ID "odom" passed to canTransform argument target_frame - frame does not exist
    [amcl-7] [WARN] [1656666935.892714680] [amcl]: New subscription discovered on topic '/particle_cloud', requesting incompatible QoS. No messages will be sent to it. Last incompatible policy: RELIABILITY_QOS_POLICY
    [controller_server-9] [INFO] [1656666936.357457053] [local_costmap.local_costmap]: Timed out waiting for transform from base_link to odom to become available, tf error: Invalid frame ID "odom" passed to canTransform argument target_frame - frame does not exist
    [controller_server-9] [INFO] [1656666936.857440873] [local_costmap.local_costmap]: Timed out waiting for transform from base_link to odom to become available, tf error: Invalid frame ID "odom" passed to canTransform argument target_frame - frame does not exist
    [spawn_entity.py-3] [INFO] [1656666936.872330616] [spawn_entity]: Calling service /spawn_entity
    [rviz2-5] [INFO] [1656666936.939009725] [rviz2]: Trying to create a map of size 384 x 384 using 1 swatches
    [rviz2-5] [ERROR] [1656666936.940929323] [rviz2]: Vertex Program:rviz/glsl120/indexed_8bit_image.vert Fragment Program:rviz/glsl120/indexed_8bit_image.frag GLSL link result : 
    [rviz2-5] active samplers with a different type refer to the same texture image unit
    [spawn_entity.py-3] [INFO] [1656666937.341430578] [spawn_entity]: Spawn status: SpawnEntity: Successfully spawned entity [turtlebot3_waffle]
    [controller_server-9] [INFO] [1656666937.357425244] [local_costmap.local_costmap]: Timed out waiting for transform from base_link to odom to become available, tf error: Invalid frame ID "odom" passed to canTransform argument target_frame - frame does not exist
    [INFO] [spawn_entity.py-3]: process has finished cleanly [pid 28426]
    [gzserver-1] [INFO] [1656666937.636194543] [intel_realsense_r200_depth_driver]: Publishing camera info to [/intel_realsense_r200_depth/camera_info]
    [gzserver-1] [INFO] [1656666937.637957468] [intel_realsense_r200_depth_driver]: Publishing depth camera info to [/intel_realsense_r200_depth/depth/camera_info]
    [gzserver-1] [INFO] [1656666937.639989775] [intel_realsense_r200_depth_driver]: Publishing pointcloud to [/intel_realsense_r200_depth/points]
    [gzserver-1] [INFO] [1656666937.774939695] [turtlebot3_diff_drive]: Wheel pair 1 separation set to [0.287000m]
    [gzserver-1] [INFO] [1656666937.775009149] [turtlebot3_diff_drive]: Wheel pair 1 diameter set to [0.066000m]
    [gzserver-1] [INFO] [1656666937.787231268] [turtlebot3_diff_drive]: Subscribed to [/cmd_vel]
    [gzserver-1] [INFO] [1656666937.793000781] [turtlebot3_diff_drive]: Advertise odometry on [/odom]
    [gzserver-1] [INFO] [1656666937.801122002] [turtlebot3_diff_drive]: Publishing odom transforms between [odom] and [base_footprint]
    [gzserver-1] [INFO] [1656666937.820159696] [turtlebot3_joint_state]: Going to publish joint [wheel_left_joint]
    [gzserver-1] [INFO] [1656666937.820259777] [turtlebot3_joint_state]: Going to publish joint [wheel_right_joint]
    [controller_server-9] [INFO] [1656666937.857415765] [local_costmap.local_costmap]: Timed out waiting for transform from base_link to odom to become available, tf error: Invalid frame ID "odom" passed to canTransform argument target_frame - frame does not exist
    [controller_server-9] [INFO] [1656666938.408777033] [controller_server]: Creating bond (controller_server) to lifecycle manager.
    [lifecycle_manager-15] [INFO] [1656666938.517407299] [lifecycle_manager_navigation]: Server controller_server connected with bond.
    [lifecycle_manager-15] [INFO] [1656666938.517482778] [lifecycle_manager_navigation]: Activating smoother_server
    [smoother_server-10] [INFO] [1656666938.518025752] [smoother_server]: Creating bond (smoother_server) to lifecycle manager.
    [lifecycle_manager-15] [INFO] [1656666938.623589805] [lifecycle_manager_navigation]: Server smoother_server connected with bond.
    [lifecycle_manager-15] [INFO] [1656666938.623632404] [lifecycle_manager_navigation]: Activating dynamic/planner_server
    [planner_server-11] [INFO] [1656666938.624053540] [dynamic.global_costmap.global_costmap]: Checking transform
    [planner_server-11] [INFO] [1656666938.624096052] [dynamic.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
    [planner_server-11] [INFO] [1656666939.124168590] [dynamic.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
    [planner_server-11] [INFO] [1656666939.624149477] [dynamic.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
    [amcl-7] [WARN] [1656666939.853090824] [amcl]: AMCL cannot publish a pose or update the transform. Please set the initial pose...
    [rviz2-5] [INFO] [1656666940.059350719] [rviz]: Message Filter dropping message: frame 'base_scan' at time 0.396 for reason 'discarding message because the queue is full'
    [planner_server-11] [INFO] [1656666940.124158349] [dynamic.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
    [rviz2-5] [INFO] [1656666940.251813312] [rviz]: Message Filter dropping message: frame 'base_scan' at time 0.596 for reason 'discarding message because the queue is full'
    [rviz2-5] [INFO] [1656666940.383326541] [rviz]: Message Filter dropping message: frame 'odom' at time 0.706 for reason 'discarding message because the queue is full'
    [rviz2-5] [INFO] [1656666940.491633002] [rviz]: Message Filter dropping message: frame 'base_scan' at time 0.796 for reason 'discarding message because the queue is full'
    [rviz2-5] [INFO] [1656666940.574676567] [rviz]: Message Filter dropping message: frame 'odom' at time 0.910 for reason 'discarding message because the queue is full'
    [planner_server-11] [INFO] [1656666940.624192382] [dynamic.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
    [rviz2-5] [INFO] [1656666940.668204122] [rviz]: Message Filter dropping message: frame 'base_scan' at time 0.996 for reason 'discarding message because the queue is full'
    [rviz2-5] [INFO] [1656666940.764007556] [rviz]: Message Filter dropping message: frame 'odom' at time 1.114 for reason 'discarding message because the queue is full'
    [rviz2-5] [INFO] [1656666940.859687078] [rviz]: Message Filter dropping message: frame 'base_scan' at time 1.196 for reason 'discarding message because the queue is full'
    [rviz2-5] [INFO] [1656666940.987461558] [rviz]: Message Filter dropping message: frame 'odom' at time 1.284 for reason 'discarding message because the queue is full'
    [rviz2-5] [INFO] [1656666941.084274854] [rviz]: Message Filter dropping message: frame 'base_scan' at time 1.396 for reason 'discarding message because the queue is full'
    [planner_server-11] [INFO] [1656666941.124152418] [dynamic.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
    [rviz2-5] [INFO] [1656666941.180095891] [rviz]: Message Filter dropping message: frame 'odom' at time 1.488 for reason 'discarding message because the queue is full'
    [rviz2-5] [INFO] [1656666941.279164679] [rviz]: Message Filter dropping message: frame 'base_scan' at time 1.597 for reason 'discarding message because the queue is full'
    [rviz2-5] [INFO] [1656666941.372194943] [rviz]: Message Filter dropping message: frame 'odom' at time 1.692 for reason 'discarding message because the queue is full'
    [rviz2-5] [INFO] [1656666941.467948999] [rviz]: Message Filter dropping message: frame 'base_scan' at time 1.796 for reason 'discarding message because the queue is full'
    [rviz2-5] [INFO] [1656666941.563920999] [rviz]: Message Filter dropping message: frame 'odom' at time 1.896 for reason 'discarding message because the queue is full'
    [planner_server-11] [INFO] [1656666941.624151352] [dynamic.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
    [rviz2-5] [INFO] [1656666941.692232508] [rviz]: Message Filter dropping message: frame 'base_scan' at time 1.996 for reason 'discarding message because the queue is full'
    [rviz2-5] [INFO] [1656666941.787765532] [rviz]: Message Filter dropping message: frame 'odom' at time 2.100 for reason 'discarding message because the queue is full'
    [rviz2-5] [INFO] [1656666941.883748243] [rviz]: Message Filter dropping message: frame 'base_scan' at time 2.196 for reason 'discarding message because the queue is full'
    [rviz2-5] [INFO] [1656666941.979692801] [rviz]: Message Filter dropping message: frame 'odom' at time 2.304 for reason 'discarding message because the queue is full'
    [amcl-7] [WARN] [1656666942.078108042] [amcl]: AMCL cannot publish a pose or update the transform. Please set the initial pose...
    [rviz2-5] [INFO] [1656666942.079213699] [rviz]: Message Filter dropping message: frame 'base_scan' at time 2.396 for reason 'discarding message because the queue is full'
    [planner_server-11] [INFO] [1656666942.124150585] [dynamic.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
    [rviz2-5] [INFO] [1656666942.171996645] [rviz]: Message Filter dropping message: frame 'odom' at time 2.474 for reason 'discarding message because the queue is full'
    [rviz2-5] [INFO] [1656666942.268072268] [rviz]: Message Filter dropping message: frame 'base_scan' at time 2.596 for reason 'discarding message because the queue is full'
    [rviz2-5] [INFO] [1656666942.363948428] [rviz]: Message Filter dropping message: frame 'odom' at time 2.678 for reason 'discarding message because the queue is full'
    [rviz2-5] [INFO] [1656666942.491866245] [rviz]: Message Filter dropping message: frame 'base_scan' at time 2.796 for reason 'discarding message because the queue is full'
    [rviz2-5] [INFO] [1656666942.588231778] [rviz]: Message Filter dropping message: frame 'odom' at time 2.882 for reason 'discarding message because the queue is full'
    [planner_server-11] [INFO] [1656666942.624149780] [dynamic.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
    [rviz2-5] [INFO] [1656666942.683799201] [rviz]: Message Filter dropping message: frame 'base_scan' at time 2.996 for reason 'discarding message because the queue is full'
    [rviz2-5] [INFO] [1656666942.779233577] [rviz]: Message Filter dropping message: frame 'odom' at time 3.086 for reason 'discarding message because the queue is full'
    [rviz2-5] [INFO] [1656666942.878052615] [rviz]: Message Filter dropping message: frame 'base_scan' at time 3.196 for reason 'discarding message because the queue is full'
    [rviz2-5] [INFO] [1656666942.971891553] [rviz]: Message Filter dropping message: frame 'odom' at time 3.290 for reason 'discarding message because the queue is full'
    [rviz2-5] [INFO] [1656666943.100294307] [rviz]: Message Filter dropping message: frame 'base_scan' at time 3.396 for reason 'discarding message because the queue is full'
    [planner_server-11] [INFO] [1656666943.124150587] [dynamic.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
    [rviz2-5] [INFO] [1656666943.164085756] [rviz]: Message Filter dropping message: frame 'odom' at time 3.494 for reason 'discarding message because the queue is full'
    [rviz2-5] [INFO] [1656666943.291949644] [rviz]: Message Filter dropping message: frame 'base_scan' at time 3.596 for reason 'discarding message because the queue is full'
    [rviz2-5] [INFO] [1656666943.387843376] [rviz]: Message Filter dropping message: frame 'odom' at time 3.664 for reason 'discarding message because the queue is full'
    [rviz2-5] [INFO] [1656666943.515894133] [rviz]: Message Filter dropping message: frame 'base_scan' at time 3.796 for reason 'discarding message because the queue is full'
    [rviz2-5] [INFO] [1656666943.579822976] [rviz]: Message Filter dropping message: frame 'odom' at time 3.868 for reason 'discarding message because the queue is full'
    [planner_server-11] [INFO] [1656666943.624152928] [dynamic.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
    [rviz2-5] [INFO] [1656666943.707964162] [rviz]: Message Filter dropping message: frame 'base_scan' at time 3.996 for reason 'discarding message because the queue is full'
    [rviz2-5] [INFO] [1656666943.771850358] [rviz]: Message Filter dropping message: frame 'odom' at time 4.072 for reason 'discarding message because the queue is full'
    [rviz2-5] [INFO] [1656666943.900103414] [rviz]: Message Filter dropping message: frame 'base_scan' at time 4.196 for reason 'discarding message because the queue is full'
    [rviz2-5] [INFO] [1656666943.963296040] [rviz]: Message Filter dropping message: frame 'odom' at time 4.276 for reason 'discarding message because the queue is full'
    [rviz2-5] [INFO] [1656666944.091886847] [rviz]: Message Filter dropping message: frame 'base_scan' at time 4.396 for reason 'discarding message because the queue is full'
    [planner_server-11] [INFO] [1656666944.124151329] [dynamic.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
    [rviz2-5] [INFO] [1656666944.188210494] [rviz]: Message Filter dropping message: frame 'odom' at time 4.480 for reason 'discarding message because the queue is full'
    [amcl-7] [WARN] [1656666944.313552731] [amcl]: AMCL cannot publish a pose or update the transform. Please set the initial pose...
    [rviz2-5] [INFO] [1656666944.315886662] [rviz]: Message Filter dropping message: frame 'base_scan' at time 4.596 for reason 'discarding message because the queue is full'
    [rviz2-5] [INFO] [1656666944.379883047] [rviz]: Message Filter dropping message: frame 'odom' at time 0.694 for reason 'discarding message because the queue is full'
    [rviz2-5] [INFO] [1656666944.379952816] [rviz]: Message Filter dropping message: frame 'odom' at time 4.684 for reason 'discarding message because the queue is full'
    [rviz2-5] [INFO] [1656666944.500809320] [rviz2]: Setting estimate pose: Frame:map, Position(-1.90513, -0.160157, 0), Orientation(0, 0, -0.0221002, 0.999756) = Angle: -0.044204
    [amcl-7] [WARN] [1656666944.501310094] [amcl]: Failed to transform initial pose in time (Lookup would require extrapolation into the future.  Requested time 1656666944.500773 but the latest data is at time 6.792000, when looking up transform from frame [odom] to frame [base_footprint])
    [amcl-7] [INFO] [1656666944.501343404] [amcl]: Setting pose (6.762000): -1.905 -0.160 -0.044
    [rviz2-5] [INFO] [1656666944.507684060] [rviz]: Message Filter dropping message: frame 'base_scan' at time 4.797 for reason 'discarding message because the queue is full'
    [rviz2-5] [INFO] [1656666944.571333362] [rviz]: Message Filter dropping message: frame 'odom' at time 4.854 for reason 'discarding message because the queue is full'
    [planner_server-11] [INFO] [1656666944.624155327] [dynamic.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
    [rviz2-5] [INFO] [1656666944.699463689] [rviz]: Message Filter dropping message: frame 'base_scan' at time 4.996 for reason 'discarding message because the queue is full'
    [rviz2-5] [INFO] [1656666944.763863323] [rviz]: Message Filter dropping message: frame 'odom' at time 5.058 for reason 'discarding message because the queue is full'
    [rviz2-5] [INFO] [1656666944.891481147] [rviz]: Message Filter dropping message: frame 'base_scan' at time 5.197 for reason 'discarding message because the queue is full'
    [rviz2-5] [INFO] [1656666944.987703644] [rviz]: Message Filter dropping message: frame 'odom' at time 1.290 for reason 'discarding message because the queue is full'
    [rviz2-5] [INFO] [1656666944.987778962] [rviz]: Message Filter dropping message: frame 'odom' at time 5.262 for reason 'discarding message because the queue is full'
    [rviz2-5] [INFO] [1656666945.115851311] [rviz]: Message Filter dropping message: frame 'base_scan' at time 5.396 for reason 'discarding message because the queue is full'
    [planner_server-11] [INFO] [1656666945.124150507] [dynamic.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
    [rviz2-5] [INFO] [1656666945.179543619] [rviz]: Message Filter dropping message: frame 'odom' at time 5.466 for reason 'discarding message because the queue is full'
    [rviz2-5] [INFO] [1656666945.307389543] [rviz]: Message Filter dropping message: frame 'base_scan' at time 5.596 for reason 'discarding message because the queue is full'
    [rviz2-5] [INFO] [1656666945.371843839] [rviz]: Message Filter dropping message: frame 'odom' at time 5.670 for reason 'discarding message because the queue is full'
    [rviz2-5] [INFO] [1656666945.500119257] [rviz]: Message Filter dropping message: frame 'base_scan' at time 5.796 for reason 'discarding message because the queue is full'
    [rviz2-5] [INFO] [1656666945.563573917] [rviz]: Message Filter dropping message: frame 'odom' at time 1.885 for reason 'discarding message because the queue is full'
    [rviz2-5] [INFO] [1656666945.563644216] [rviz]: Message Filter dropping message: frame 'odom' at time 5.840 for reason 'discarding message because the queue is full'
    [rviz2-5] [INFO] [1656666945.564893023] [rviz2]: Trying to create a map of size 60 x 60 using 1 swatches
    [planner_server-11] [INFO] [1656666945.624150808] [dynamic.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
    [planner_server-11] [INFO] [1656666946.124152772] [dynamic.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
    [planner_server-11] [INFO] [1656666946.624155369] [dynamic.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
    [planner_server-11] [INFO] [1656666947.124156076] [dynamic.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
    [planner_server-11] [INFO] [1656666947.624149214] [dynamic.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
    [planner_server-11] [INFO] [1656666948.124150690] [dynamic.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
    [planner_server-11] [INFO] [1656666948.624150917] [dynamic.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
    [planner_server-11] [INFO] [1656666949.124149829] [dynamic.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
    [rviz2-5] [INFO] [1656666949.353334796] [rviz]: Message Filter dropping message: frame 'odom' at time 2.486 for reason 'the timestamp on the message is earlier than all the data in the transform cache'
    [planner_server-11] [INFO] [1656666949.624152335] [dynamic.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
    [rviz2-5] [INFO] [1656666949.932801343] [rviz]: Message Filter dropping message: frame 'odom' at time 3.079 for reason 'the timestamp on the message is earlier than all the data in the transform cache'
    [planner_server-11] [INFO] [1656666950.124148415] [dynamic.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
    [rviz2-5] [INFO] [1656666950.544178695] [rviz]: Message Filter dropping message: frame 'odom' at time 3.681 for reason 'the timestamp on the message is earlier than all the data in the transform cache'
    [planner_server-11] [INFO] [1656666950.624147681] [dynamic.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
    [planner_server-11] [INFO] [1656666951.124152502] [dynamic.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
    [rviz2-5] [INFO] [1656666951.159417381] [rviz]: Message Filter dropping message: frame 'odom' at time 4.279 for reason 'the timestamp on the message is earlier than all the data in the transform cache'
    [planner_server-11] [INFO] [1656666951.624147563] [dynamic.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
    [rviz2-5] [INFO] [1656666951.738468959] [rviz]: Message Filter dropping message: frame 'odom' at time 4.876 for reason 'the timestamp on the message is earlier than all the data in the transform cache'
    [planner_server-11] [INFO] [1656666952.124150396] [dynamic.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
    [rviz2-5] [INFO] [1656666952.355093859] [rviz]: Message Filter dropping message: frame 'odom' at time 5.469 for reason 'the timestamp on the message is earlier than all the data in the transform cache'
    [planner_server-11] [INFO] [1656666952.624147903] [dynamic.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
    [rviz2-5] [INFO] [1656666952.978604801] [rviz]: Message Filter dropping message: frame 'odom' at time 6.044 for reason 'the timestamp on the message is earlier than all the data in the transform cache'
    [rviz2-5] [INFO] [1656666952.978655802] [rviz]: Message Filter dropping message: frame 'odom' at time 6.062 for reason 'the timestamp on the message is earlier than all the data in the transform cache'
    [planner_server-11] [INFO] [1656666953.124147924] [dynamic.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
    [rviz2-5] [INFO] [1656666953.182936956] [rviz]: Message Filter dropping message: frame 'odom' at time 6.248 for reason 'the timestamp on the message is earlier than all the data in the transform cache'
    [rviz2-5] [INFO] [1656666953.353759681] [rviz]: Message Filter dropping message: frame 'odom' at time 6.452 for reason 'the timestamp on the message is earlier than all the data in the transform cache'
    [rviz2-5] [INFO] [1656666953.559708355] [rviz]: Message Filter dropping message: frame 'odom' at time 6.656 for reason 'the timestamp on the message is earlier than all the data in the transform cache'
    [rviz2-5] [INFO] [1656666953.559770942] [rviz]: Message Filter dropping message: frame 'odom' at time 6.662 for reason 'the timestamp on the message is earlier than all the data in the transform cache'
    [planner_server-11] [INFO] [1656666953.624149624] [dynamic.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
    [rviz2-5] [INFO] [1656666953.764712037] [rviz]: Message Filter dropping message: frame 'base_scan' at time 5.996 for reason 'the timestamp on the message is earlier than all the data in the transform cache'
    [rviz2-5] [INFO] [1656666953.764949037] [rviz]: Message Filter dropping message: frame 'odom' at time 6.860 for reason 'the timestamp on the message is earlier than all the data in the transform cache'
    [rviz2-5] [INFO] [1656666953.974111159] [rviz]: Message Filter dropping message: frame 'base_scan' at time 6.197 for reason 'the timestamp on the message is earlier than all the data in the transform cache'
    [rviz2-5] [INFO] [1656666953.974279019] [rviz]: Message Filter dropping message: frame 'odom' at time 7.064 for reason 'the timestamp on the message is earlier than all the data in the transform cache'
    [planner_server-11] [INFO] [1656666954.124193694] [dynamic.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
    [rviz2-5] [INFO] [1656666954.178293592] [rviz]: Message Filter dropping message: frame 'base_scan' at time 6.396 for reason 'the timestamp on the message is earlier than all the data in the transform cache'
    [rviz2-5] [INFO] [1656666954.178611185] [rviz]: Message Filter dropping message: frame 'odom' at time 7.262 for reason 'the timestamp on the message is earlier than all the data in the transform cache'
    [rviz2-5] [INFO] [1656666954.178657261] [rviz]: Message Filter dropping message: frame 'odom' at time 7.234 for reason 'the timestamp on the message is earlier than all the data in the transform cache'
    [rviz2-5] [INFO] [1656666954.382634040] [rviz]: Message Filter dropping message: frame 'base_scan' at time 6.596 for reason 'the timestamp on the message is earlier than all the data in the transform cache'
    [rviz2-5] [INFO] [1656666954.382863475] [rviz]: Message Filter dropping message: frame 'odom' at time 7.438 for reason 'the timestamp on the message is earlier than all the data in the transform cache'
    [rviz2-5] [INFO] [1656666954.587116898] [rviz]: Message Filter dropping message: frame 'base_scan' at time 6.796 for reason 'the timestamp on the message is earlier than all the data in the transform cache'
    [rviz2-5] [INFO] [1656666954.587306027] [rviz]: Message Filter dropping message: frame 'odom' at time 7.642 for reason 'the timestamp on the message is earlier than all the data in the transform cache'
    [planner_server-11] [INFO] [1656666954.624155641] [dynamic.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
    [rviz2-5] [INFO] [1656666954.792417291] [rviz]: Message Filter dropping message: frame 'base_scan' at time 6.996 for reason 'the timestamp on the message is earlier than all the data in the transform cache'
    [rviz2-5] [INFO] [1656666955.000282900] [rviz]: Message Filter dropping message: frame 'base_scan' at time 7.196 for reason 'the timestamp on the message is earlier than all the data in the transform cache'
    [planner_server-11] [INFO] [1656666955.124149994] [dynamic.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
    [rviz2-5] [INFO] [1656666955.171004657] [rviz]: Message Filter dropping message: frame 'base_scan' at time 7.396 for reason 'the timestamp on the message is earlier than all the data in the transform cache'
    [rviz2-5] [INFO] [1656666955.382080713] [rviz]: Message Filter dropping message: frame 'base_scan' at time 7.596 for reason 'the timestamp on the message is earlier than all the data in the transform cache'
    [planner_server-11] [INFO] [1656666955.624158552] [dynamic.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
    [planner_server-11] [INFO] [1656666956.124109940] [dynamic.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
    [planner_server-11] [INFO] [1656666956.624153520] [dynamic.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
    [planner_server-11] [INFO] [1656666957.124154636] [dynamic.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
    [planner_server-11] [INFO] [1656666957.624129438] [dynamic.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
    [planner_server-11] [INFO] [1656666958.124155024] [dynamic.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
    [planner_server-11] [INFO] [1656666958.624152467] [dynamic.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
    [planner_server-11] [INFO] [1656666959.124157000] [dynamic.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
    [planner_server-11] [INFO] [1656666959.624153861] [dynamic.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
    [planner_server-11] [INFO] [1656666960.124155472] [dynamic.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
    [planner_server-11] [INFO] [1656666960.624154107] [dynamic.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
    [planner_server-11] [INFO] [1656666961.124153041] [dynamic.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
    [planner_server-11] [INFO] [1656666961.624152579] [dynamic.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
    [planner_server-11] [INFO] [1656666962.124152832] [dynamic.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
    [planner_server-11] [INFO] [1656666962.624140863] [dynamic.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
    [planner_server-11] [INFO] [1656666963.124160140] [dynamic.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
    [planner_server-11] [INFO] [1656666963.624148841] [dynamic.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
    [planner_server-11] [INFO] [1656666964.124150617] [dynamic.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
    [planner_server-11] [INFO] [1656666964.624152180] [dynamic.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

But, when I echo the tf from base_link to map, it seems no problem.

~$ ros2 run tf2_ros tf2_echo map base_link
[INFO] [1656667241.326635612] [tf2_echo]: Waiting for transform map ->  base_link: Invalid frame ID "map" passed to canTransform argument target_frame - frame does not exist
At time 302.626000000
- Translation: [-1.901, -0.189, 0.010]
- Rotation: in Quaternion [-0.000, -0.000, -0.017, 1.000]
- Rotation: in RPY (radian) [-0.000, -0.000, -0.035]
- Rotation: in RPY (degree) [-0.001, -0.000, -1.998]
- Matrix:
  0.999  0.035 -0.000 -1.901
 -0.035  0.999  0.000 -0.189
  0.000 -0.000  1.000  0.010
  0.000  0.000  0.000  1.000
At time 303.612000000
- Translation: [-1.901, -0.189, 0.010]
- Rotation: in Quaternion [-0.000, -0.000, -0.017, 1.000]
- Rotation: in RPY (radian) [-0.000, -0.000, -0.035]
- Rotation: in RPY (degree) [-0.002, -0.000, -1.995]
- Matrix:
  0.999  0.035 -0.000 -1.901
 -0.035  0.999  0.000 -0.189
  0.000 -0.000  1.000  0.010
  0.000  0.000  0.000  1.000
At time 304.598000000
- Translation: [-1.901, -0.189, 0.010]
- Rotation: in Quaternion [-0.000, 0.000, -0.017, 1.000]
- Rotation: in RPY (radian) [-0.000, 0.000, -0.035]
- Rotation: in RPY (degree) [-0.001, 0.000, -1.992]
- Matrix:
  0.999  0.035  0.000 -1.901
 -0.035  0.999  0.000 -0.189
 -0.000 -0.000  1.000  0.010
  0.000  0.000  0.000  1.000
SteveMacenski commented 2 years ago

I suggest asking on ROS Answers and start some debugging on your side. This could be such a huge litany of user issues of not dotting your "I"s and crossing your "T"s. There's a chance this could be a Nav2 related issue, but that seems doubtful. Make sure you know what applying that namespace is launch is actually going and check out all the topics and data flow in your compute network and see if something is fishy.