Note: For any Isaac Lab topics, please submit your topic to its GitHub repo (GitHub - isaac-sim/IsaacLab: Unified framework for robot learning built on NVIDIA Isaac Sim) following the instructions provided on Isaac Lab’s Contributing Guidelines (Contribution Guidelines — Isaac Lab Documentation).
Please provide all relevant details below before submitting your post. This will help the community provide more accurate and timely assistance. After submitting, you can check the appropriate boxes. Remember, you can always edit your post later to include additional information if needed.
Isaac Sim Version
4.5.0
[V] 4.2.0
4.1.0
4.0.0
4.5.0
2023.1.1
2023.1.0-hotfix.1
Other (please specify):
Operating System
[V] Ubuntu 22.04
Ubuntu 20.04
Windows 11
Windows 10
Other (please specify):
GPU Information
- Model: RTX 4080 super (+Jetson AGX Orin)
- Driver Version: 570.124.04
Topic Description
Detailed Description
(Describe the issue in detail, including what you were trying to do, what you expected to happen, and what actually happened)
Hello, I’ve been exploring the world of Isaac ROS with IsaacSim! While following the tutorials on docking with nova carter in IsaacSim (using apriltag and foundationpose), I found that it is not working as intended.
When I send the mission command, the robot usually stops and makes a turn. I followed the IsaacSim setup instructions, including docking station placement and lidar configuration, and I had no problem running each of the DNN models (ess, rt-detr, foundationpose).
The error message I get is like this:
[controller_server-7] [ERROR] [1748604326.447607331] [tf_help]: Transform data too old when converting from odom to map
[controller_server-7] [ERROR] [1748604326.447683169] [tf_help]: Data time: 5s 66666930ns, Transform time: 4s 850031451ns
[controller_server-7] [WARN] [1748604326.447878909] [controller_server]: Unable to transform robot pose into global plan's frame
Using the ros2 run tf2_ros tf2_echo map odom
command, I found that the transformed data being sent lags behind the sim time, which prevents the robot from operating properly.
My system setup is as follows:
- IsaacSim on node A: x86_64 (13th Gen Intel(R) Core™ i7-13700K) with RTX 4080 super
- isaac ros on node B: Jetson AGX Orin 64GB
- Both nodes directly connected with 1Gbps Ethernet, using CyclonDDS for RMW
I’m suspecting the network, because when I run both IsaacSim and Isaac ROS on the same node (with an RTX 3090 for sufficient GPU memory), the transformed data is produced in a timely manner and the docking succeeds. Also, it is not an issue with the JAO, since I was able to reproduce the same problem with another x86_64 machine equipped with an RTX 3090.
Could you please provide any hints on the casuse of this problem?
Thank you.
Steps to Reproduce
- Run Isaac Sim on desktop with RTX 4080 super
- Run
(Add more steps as needed)
Error Messages
(If applicable, copy and paste any error messages you received)
Intentionally deleted messages regarding component_container_mt to reduce the log.
root@ubuntu:/workspaces/isaac_ros-dev# ros2 launch nova_carter_docking docking_with_fp_sim.launch.py init_pose_x:=-2.0 init_pose_y:=14.0 init_pose_yaw:=3.14 launch_rviz:=True
[INFO] [launch]: All log files can be found below /home/admin/.ros/log/2025-05-30-21-12-17-250438-ubuntu-31317
[INFO] [launch]: Default logging verbosity is set to INFO
[INFO] [component_container_mt-1]: process started with pid [31333]
[INFO] [rviz2-2]: process started with pid [31335]
[INFO] [fp_dock_pose_publisher.py-3]: process started with pid [31337]
[INFO] [map_server-4]: process started with pid [31339]
[INFO] [amcl-5]: process started with pid [31341]
[INFO] [lifecycle_manager-6]: process started with pid [31343]
[INFO] [controller_server-7]: process started with pid [31345]
[INFO] [smoother_server-8]: process started with pid [31347]
[INFO] [planner_server-9]: process started with pid [31349]
[INFO] [behavior_server-10]: process started with pid [31351]
[INFO] [bt_navigator-11]: process started with pid [31353]
[INFO] [waypoint_follower-12]: process started with pid [31410]
[INFO] [velocity_smoother-13]: process started with pid [31460]
[INFO] [lifecycle_manager-14]: process started with pid [31463]
[INFO] [opennav_docking-15]: process started with pid [31466]
[INFO] [lifecycle_manager-16]: process started with pid [31476]
[rviz2-2] QStandardPaths: XDG_RUNTIME_DIR not set, defaulting to '/tmp/runtime-root'
[map_server-4] [INFO] [1748607137.829164431] [map_server]:
[map_server-4] map_server lifecycle node launched.
[map_server-4] Waiting on external lifecycle transitions to activate
[map_server-4] See https://design.ros2.org/articles/node_lifecycle.html for more information.
[map_server-4] [INFO] [1748607137.829511114] [map_server]: Creating
[map_server-4] [INFO] [1748607137.841715374] [map_server]: Configuring
[map_server-4] [INFO] [1748607137.841897836] [map_io]: Loading yaml file: /opt/ros/humble/share/isaac_ros_vda5050_nav2_client_bringup/maps/carter_warehouse_navigation.yaml
[map_server-4] [INFO] [1748607137.842270343] [map_io]: resolution: 0.05
[map_server-4] [INFO] [1748607137.842288455] [map_io]: origin[0]: -11.975
[map_server-4] [INFO] [1748607137.842294918] [map_io]: origin[1]: -17.975
[map_server-4] [INFO] [1748607137.842299590] [map_io]: origin[2]: 0
[map_server-4] [INFO] [1748607137.842304198] [map_io]: free_thresh: 0.196
[map_server-4] [INFO] [1748607137.842308550] [map_io]: occupied_thresh: 0.65
[map_server-4] [INFO] [1748607137.842314118] [map_io]: mode: trinary
[map_server-4] [INFO] [1748607137.842320102] [map_io]: negate: 0
[map_server-4] [INFO] [1748607137.843044445] [map_io]: Loading image_file: /opt/ros/humble/share/isaac_ros_vda5050_nav2_client_bringup/maps/carter_warehouse_navigation.png
[amcl-5] [INFO] [1748607137.834534026] [amcl]:
[amcl-5] amcl lifecycle node launched.
[amcl-5] Waiting on external lifecycle transitions to activate
[amcl-5] See https://design.ros2.org/articles/node_lifecycle.html for more information.
[amcl-5] [INFO] [1748607137.836858796] [amcl]: Creating
[lifecycle_manager-6] [INFO] [1748607137.813280154] [lifecycle_manager_localization]: Creating
[lifecycle_manager-6] [INFO] [1748607137.821371699] [lifecycle_manager_localization]: Creating and initializing lifecycle service clients
[lifecycle_manager-6] [INFO] [1748607137.829908165] [lifecycle_manager_localization]: Starting managed nodes bringup...
[lifecycle_manager-6] [INFO] [1748607137.830021476] [lifecycle_manager_localization]: Configuring map_server
[controller_server-7] [INFO] [1748607137.819772807] [controller_server]:
[controller_server-7] controller_server lifecycle node launched.
[controller_server-7] Waiting on external lifecycle transitions to activate
[controller_server-7] See https://design.ros2.org/articles/node_lifecycle.html for more information.
[controller_server-7] [INFO] [1748607137.826639151] [controller_server]: Creating controller server
[controller_server-7] [INFO] [1748607137.832854655] [local_costmap.local_costmap]:
[controller_server-7] local_costmap lifecycle node launched.
[controller_server-7] Waiting on external lifecycle transitions to activate
[controller_server-7] See https://design.ros2.org/articles/node_lifecycle.html for more information.
[controller_server-7] [INFO] [1748607137.834046544] [local_costmap.local_costmap]: Creating Costmap
[smoother_server-8] [INFO] [1748607137.827437029] [smoother_server]:
[smoother_server-8] smoother_server lifecycle node launched.
[smoother_server-8] Waiting on external lifecycle transitions to activate
[smoother_server-8] See https://design.ros2.org/articles/node_lifecycle.html for more information.
[smoother_server-8] [INFO] [1748607137.829349228] [smoother_server]: Creating smoother server
[planner_server-9] [INFO] [1748607137.817169736] [planner_server]:
[planner_server-9] planner_server lifecycle node launched.
[planner_server-9] Waiting on external lifecycle transitions to activate
[planner_server-9] See https://design.ros2.org/articles/node_lifecycle.html for more information.
[planner_server-9] [INFO] [1748607137.819134863] [planner_server]: Creating
[planner_server-9] [INFO] [1748607137.827615459] [global_costmap.global_costmap]:
[planner_server-9] global_costmap lifecycle node launched.
[planner_server-9] Waiting on external lifecycle transitions to activate
[planner_server-9] See https://design.ros2.org/articles/node_lifecycle.html for more information.
[planner_server-9] [INFO] [1748607137.828378105] [global_costmap.global_costmap]: Creating Costmap
[behavior_server-10] [INFO] [1748607137.826199477] [behavior_server]:
[behavior_server-10] behavior_server lifecycle node launched.
[behavior_server-10] Waiting on external lifecycle transitions to activate
[behavior_server-10] See https://design.ros2.org/articles/node_lifecycle.html for more information.
[bt_navigator-11] [INFO] [1748607137.831062070] [bt_navigator]:
[bt_navigator-11] bt_navigator lifecycle node launched.
[bt_navigator-11] Waiting on external lifecycle transitions to activate
[bt_navigator-11] See https://design.ros2.org/articles/node_lifecycle.html for more information.
[bt_navigator-11] [INFO] [1748607137.831226932] [bt_navigator]: Creating
[waypoint_follower-12] [INFO] [1748607137.851298995] [waypoint_follower]:
[waypoint_follower-12] waypoint_follower lifecycle node launched.
[waypoint_follower-12] Waiting on external lifecycle transitions to activate
[waypoint_follower-12] See https://design.ros2.org/articles/node_lifecycle.html for more information.
[waypoint_follower-12] [INFO] [1748607137.852531363] [waypoint_follower]: Creating
[velocity_smoother-13] [INFO] [1748607137.866196564] [velocity_smoother]:
[velocity_smoother-13] velocity_smoother lifecycle node launched.
[velocity_smoother-13] Waiting on external lifecycle transitions to activate
[velocity_smoother-13] See https://design.ros2.org/articles/node_lifecycle.html for more information.
[lifecycle_manager-16] [INFO] [1748607137.881132181] [lifecycle_manager_docking]: Creating
[lifecycle_manager-16] [INFO] [1748607137.883236378] [lifecycle_manager_docking]: Creating and initializing lifecycle service clients
[opennav_docking-15] [INFO] [1748607137.882350405] [docking_server]:
[opennav_docking-15] docking_server lifecycle node launched.
[opennav_docking-15] Waiting on external lifecycle transitions to activate
[opennav_docking-15] See https://design.ros2.org/articles/node_lifecycle.html for more information.
[opennav_docking-15] [INFO] [1748607137.882490947] [docking_server]: Creating docking_server
[component_container_mt-1] ---
[lifecycle_manager-14] [INFO] [1748607137.912937757] [lifecycle_manager_navigation]: Creating
[lifecycle_manager-14] [INFO] [1748607137.918050172] [lifecycle_manager_navigation]: Creating and initializing lifecycle service clients
[lifecycle_manager-16] [INFO] [1748607137.929493577] [lifecycle_manager_docking]: Starting managed nodes bringup...
[lifecycle_manager-16] [INFO] [1748607137.929865573] [lifecycle_manager_docking]: Configuring docking_server
[lifecycle_manager-14] [INFO] [1748607137.943655732] [lifecycle_manager_navigation]: Starting managed nodes bringup...
[lifecycle_manager-14] [INFO] [1748607137.943758387] [lifecycle_manager_navigation]: Configuring controller_server
[controller_server-7] [INFO] [1748607137.944048527] [controller_server]: Configuring controller interface
[controller_server-7] [INFO] [1748607137.944245900] [controller_server]: getting goal checker plugins..
[controller_server-7] [INFO] [1748607137.944458442] [controller_server]: Controller frequency set to 20.0000Hz
[controller_server-7] [INFO] [1748607137.944544136] [local_costmap.local_costmap]: Configuring
[map_server-4] [INFO] [1748607137.946279314] [map_io]: Read map /opt/ros/humble/share/isaac_ros_vda5050_nav2_client_bringup/maps/carter_warehouse_navigation.png: 480 X 776 map @ 0.05 m/cell
[controller_server-7] [INFO] [1748607137.949952003] [local_costmap.local_costmap]: Using plugin "hesai_voxel_layer"
[lifecycle_manager-6] [INFO] [1748607137.952504834] [lifecycle_manager_localization]: Configuring amcl
[amcl-5] [INFO] [1748607137.952911197] [amcl]: Configuring
[amcl-5] [INFO] [1748607137.953047196] [amcl]: initTransforms
[controller_server-7] [INFO] [1748607137.955256863] [local_costmap.local_costmap]: Subscribed to Topics: pointcloud
[component_container_mt-1] ---
[amcl-5] [INFO] [1748607137.960992630] [amcl]: initPubSub
[amcl-5] [INFO] [1748607137.966133108] [amcl]: Subscribed to map topic.
[controller_server-7] [INFO] [1748607137.968598068] [local_costmap.local_costmap]: Initialized plugin "hesai_voxel_layer"
[controller_server-7] [INFO] [1748607137.968674035] [local_costmap.local_costmap]: Using plugin "front_rplidar_obstacle_layer"
[lifecycle_manager-6] [INFO] [1748607137.969837796] [lifecycle_manager_localization]: Activating map_server
[map_server-4] [INFO] [1748607137.970118433] [map_server]: Activating
[controller_server-7] [INFO] [1748607137.970743513] [local_costmap.local_costmap]: Subscribed to Topics: scan
[map_server-4] [INFO] [1748607137.972807934] [map_server]: Creating bond (map_server) to lifecycle manager.
[amcl-5] [INFO] [1748607137.972927421] [amcl]: Received a 480 X 776 map @ 0.050 m/pix
[controller_server-7] [INFO] [1748607137.979094734] [local_costmap.local_costmap]: Initialized plugin "front_rplidar_obstacle_layer"
[controller_server-7] [INFO] [1748607137.979211788] [local_costmap.local_costmap]: Using plugin "back_rplidar_obstacle_layer"
[component_container_mt-1] [INFO] ---
[controller_server-7] [INFO] [1748607137.982267237] [local_costmap.local_costmap]: Subscribed to Topics: scan
[controller_server-7] [INFO] [1748607137.989620551] [local_costmap.local_costmap]: Initialized plugin "back_rplidar_obstacle_layer"
[controller_server-7] [INFO] [1748607137.989694182] [local_costmap.local_costmap]: Using plugin "inflation_layer"
[controller_server-7] [INFO] [1748607137.990859671] [local_costmap.local_costmap]: Initialized plugin "inflation_layer"
[controller_server-7] [INFO] [1748607138.006485935] [controller_server]: Created progress_checker : progress_checker of type nav2_controller::SimpleProgressChecker
[controller_server-7] [INFO] [1748607138.008150810] [controller_server]: Created goal checker : goal_checker of type nav2_controller::SimpleGoalChecker
[controller_server-7] [INFO] [1748607138.008505045] [controller_server]: Controller Server has goal_checker goal checkers available.
[controller_server-7] [INFO] [1748607138.010716825] [controller_server]: Created controller : FollowPath of type dwb_core::DWBLocalPlanner
[controller_server-7] [INFO] [1748607138.011801323] [controller_server]: Setting transform_tolerance to 0.200000
[component_container_mt-1] [INFO] ---
[opennav_docking-15] [INFO] [1748607138.018886192] [docking_server]: Configuring docking_server
[opennav_docking-15] [INFO] [1748607138.018997679] [docking_server]: Controller frequency set to 50.0000Hz
[controller_server-7] [INFO] [1748607138.032251525] [controller_server]: Using critic "RotateToGoal" (dwb_critics::RotateToGoalCritic)
[controller_server-7] [INFO] [1748607138.033281719] [controller_server]: Critic plugin initialized
[controller_server-7] [INFO] [1748607138.033527924] [controller_server]: Using critic "Oscillation" (dwb_critics::OscillationCritic)
[opennav_docking-15] [INFO] [1748607138.034208076] [docking_server]: Created charging dock plugin nova_carter_dock of type opennav_docking::SimpleChargingDock
[controller_server-7] [INFO] [1748607138.034360170] [controller_server]: Critic plugin initialized
[controller_server-7] [INFO] [1748607138.034683334] [controller_server]: Using critic "BaseObstacle" (dwb_critics::BaseObstacleCritic)
[controller_server-7] [INFO] [1748607138.035004737] [controller_server]: Critic plugin initialized
[controller_server-7] [INFO] [1748607138.035224159] [controller_server]: Using critic "GoalAlign" (dwb_critics::GoalAlignCritic)
[controller_server-7] [INFO] [1748607138.036032372] [controller_server]: Critic plugin initialized
[controller_server-7] [INFO] [1748607138.036226962] [controller_server]: Using critic "PathAlign" (dwb_critics::PathAlignCritic)
[controller_server-7] [INFO] [1748607138.036971592] [controller_server]: Critic plugin initialized
[controller_server-7] [INFO] [1748607138.037201253] [controller_server]: Using critic "PathDist" (dwb_critics::PathDistCritic)
[controller_server-7] [INFO] [1748607138.047839517] [controller_server]: Critic plugin initialized
[opennav_docking-15] [INFO] [1748607138.047432642] [docking_server]: Loading docks from parameter file.
[controller_server-7] [INFO] [1748607138.048156185] [controller_server]: Using critic "GoalDist" (dwb_critics::GoalDistCritic)
[controller_server-7] [INFO] [1748607138.048710898] [controller_server]: Critic plugin initialized
[controller_server-7] [INFO] [1748607138.048746609] [controller_server]: Controller Server has FollowPath controllers available.
[opennav_docking-15] [INFO] [1748607138.051389775] [docking_server]: Docking Server has 1 dock types and 1 dock instances available.
[lifecycle_manager-16] [INFO] [1748607138.074648101] [lifecycle_manager_docking]: Activating docking_server
[opennav_docking-15] [INFO] [1748607138.075087104] [docking_server]: Activating docking_server
[lifecycle_manager-6] [INFO] [1748607138.082666239] [lifecycle_manager_localization]: Server map_server connected with bond.
[lifecycle_manager-6] [INFO] [1748607138.082859228] [lifecycle_manager_localization]: Activating amcl
[lifecycle_manager-14] [INFO] [1748607138.082975195] [lifecycle_manager_navigation]: Configuring smoother_server
[smoother_server-8] [INFO] [1748607138.087584960] [smoother_server]: Configuring smoother server
[amcl-5] [INFO] [1748607138.088296054] [amcl]: Activating
[amcl-5] [INFO] [1748607138.088427637] [amcl]: initialPoseReceived
[amcl-5] [INFO] [1748607138.088700593] [amcl]: Setting pose (0.000000): -2.000 14.000 3.140
[amcl-5] [INFO] [1748607138.089546406] [amcl]: Creating bond (amcl) to lifecycle manager.
[smoother_server-8] [INFO] [1748607138.092801885] [smoother_server]: Created smoother : simple_smoother of type nav2_smoother::SimpleSmoother
[smoother_server-8] [INFO] [1748607138.093213303] [smoother_server]: Smoother Server has simple_smoother smoothers available.
[lifecycle_manager-14] [INFO] [1748607138.100314332] [lifecycle_manager_navigation]: Configuring planner_server
[planner_server-9] [INFO] [1748607138.100772183] [planner_server]: Configuring
[planner_server-9] [INFO] [1748607138.100845366] [global_costmap.global_costmap]: Configuring
[planner_server-9] [INFO] [1748607138.104498503] [global_costmap.global_costmap]: Using plugin "static_layer"
[opennav_docking-15] [INFO] [1748607138.105581817] [docking_server]: Creating bond (docking_server) to lifecycle manager.
[planner_server-9] [INFO] [1748607138.113647858] [global_costmap.global_costmap]: Subscribing to the map topic (/map) with transient local durability
[planner_server-9] [INFO] [1748607138.114708100] [global_costmap.global_costmap]: Initialized plugin "static_layer"
[planner_server-9] [INFO] [1748607138.115313468] [global_costmap.global_costmap]: Using plugin "obstacle_layer"
[planner_server-9] [INFO] [1748607138.118776080] [global_costmap.global_costmap]: Subscribed to Topics: scan
[planner_server-9] [INFO] [1748607138.134810562] [global_costmap.global_costmap]: Initialized plugin "obstacle_layer"
[planner_server-9] [INFO] [1748607138.134898817] [global_costmap.global_costmap]: Using plugin "inflation_layer"
[planner_server-9] [INFO] [1748607138.136968871] [global_costmap.global_costmap]: Initialized plugin "inflation_layer"
[planner_server-9] [INFO] [1748607138.156632075] [planner_server]: Created global planner plugin GridBased of type nav2_navfn_planner/NavfnPlanner
[planner_server-9] [INFO] [1748607138.156724746] [planner_server]: Configuring plugin GridBased of type NavfnPlanner
[planner_server-9] [INFO] [1748607138.158936877] [planner_server]: Planner Server has GridBased planners available.
[lifecycle_manager-14] [INFO] [1748607138.172544959] [lifecycle_manager_navigation]: Configuring behavior_server
[behavior_server-10] [INFO] [1748607138.172910746] [behavior_server]: Configuring
[behavior_server-10] [INFO] [1748607138.193065912] [behavior_server]: Creating behavior plugin spin of type nav2_behaviors/Spin
[behavior_server-10] [INFO] [1748607138.194036779] [behavior_server]: Configuring spin
[lifecycle_manager-6] [INFO] [1748607138.208663280] [lifecycle_manager_localization]: Server amcl connected with bond.
[lifecycle_manager-6] [INFO] [1748607138.208754191] [lifecycle_manager_localization]: Managed nodes are active
[lifecycle_manager-6] [INFO] [1748607138.208776847] [lifecycle_manager_localization]: Creating bond timer...
[behavior_server-10] [INFO] [1748607138.212599102] [behavior_server]: Creating behavior plugin backup of type nav2_behaviors/BackUp
[behavior_server-10] [INFO] [1748607138.213559985] [behavior_server]: Configuring backup
[planner_server-9] [INFO] [1748607138.222972665] [global_costmap.global_costmap]: StaticLayer: Resizing costmap to 480 X 776 at 0.050000 m/pix
[behavior_server-10] [INFO] [1748607138.225176412] [behavior_server]: Creating behavior plugin drive_on_heading of type nav2_behaviors/DriveOnHeading
[behavior_server-10] [INFO] [1748607138.226283982] [behavior_server]: Configuring drive_on_heading
[behavior_server-10] [INFO] [1748607138.229260584] [behavior_server]: Creating behavior plugin wait of type nav2_behaviors/Wait
[behavior_server-10] [INFO] [1748607138.230083613] [behavior_server]: Configuring wait
[lifecycle_manager-16] [INFO] [1748607138.230755893] [lifecycle_manager_docking]: Server docking_server connected with bond.
[lifecycle_manager-16] [INFO] [1748607138.230828116] [lifecycle_manager_docking]: Managed nodes are active
[lifecycle_manager-16] [INFO] [1748607138.230849524] [lifecycle_manager_docking]: Creating bond timer...
[lifecycle_manager-14] [INFO] [1748607138.247647580] [lifecycle_manager_navigation]: Configuring bt_navigator
[bt_navigator-11] [INFO] [1748607138.248104119] [bt_navigator]: Configuring
[lifecycle_manager-14] [INFO] [1748607138.373650222] [lifecycle_manager_navigation]: Configuring waypoint_follower
[lifecycle_manager-14] [INFO] [1748607138.381535113] [lifecycle_manager_navigation]: Configuring velocity_smoother
[waypoint_follower-12] [INFO] [1748607138.374030889] [waypoint_follower]: Configuring
[waypoint_follower-12] [INFO] [1748607138.379979229] [waypoint_follower]: Created waypoint_task_executor : wait_at_waypoint of type nav2_waypoint_follower::WaitAtWaypoint
[velocity_smoother-13] [INFO] [1748607138.381884996] [velocity_smoother]: Configuring velocity smoother
[lifecycle_manager-14] [INFO] [1748607138.386798853] [lifecycle_manager_navigation]: Activating controller_server
[controller_server-7] [INFO] [1748607138.387274175] [controller_server]: Activating
[controller_server-7] [INFO] [1748607138.387433821] [local_costmap.local_costmap]: Activating
[controller_server-7] [INFO] [1748607138.387461149] [local_costmap.local_costmap]: Checking transform
[controller_server-7] [INFO] [1748607138.387505308] [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
[component_container_mt-1] [INFO] ---
[INFO] [launch_ros.actions.load_composable_nodes]: Loaded node '/resize_left_rt_detr_node' in container '/foundationpose_container'
[INFO] [launch_ros.actions.load_composable_nodes]: Loaded node '/pad_node' in container '/foundationpose_container'
[rviz2-2] [INFO] [1748607138.646515013] [rviz2]: Stereo is NOT SUPPORTED
[rviz2-2] [INFO] [1748607138.646829633] [rviz2]: OpenGl version: 4.6 (GLSL 4.6)
[INFO] [launch_ros.actions.load_composable_nodes]: Loaded node '/image_to_tensor_node' in container '/foundationpose_container'
[INFO] [launch_ros.actions.load_composable_nodes]: Loaded node '/interleaved_to_planar_node' in container '/foundationpose_container'
[rviz2-2] [INFO] [1748607138.740606799] [rviz2]: Stereo is NOT SUPPORTED
[INFO] [launch_ros.actions.load_composable_nodes]: Loaded node '/reshape_node' in container '/foundationpose_container'
[INFO] [launch_ros.actions.load_composable_nodes]: Loaded node '/rtdetr_preprocessor' in container '/foundationpose_container'
[INFO] [launch_ros.actions.load_composable_nodes]: Loaded node '/tensor_rt' in container '/foundationpose_container'
[controller_server-7] [INFO] [1748607138.887576244] [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] [launch_ros.actions.load_composable_nodes]: Loaded node '/rtdetr_decoder' in container '/foundationpose_container'
[INFO] [launch_ros.actions.load_composable_nodes]: Loaded node '/detection2_d_to_mask' in container '/foundationpose_container'
[rviz2-2] [INFO] [1748607139.071925337] [rviz2]: Stereo is NOT SUPPORTED
[controller_server-7] [INFO] [1748607139.387745225] [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] [launch_ros.actions.load_composable_nodes]: Loaded node '/resize_mask_node' in container '/foundationpose_container'
[INFO] [launch_ros.actions.load_composable_nodes]: Loaded node '/resize_left_ess_size' in container '/foundationpose_container'
[controller_server-7] [INFO] [1748607139.887566466] [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] [launch_ros.actions.load_composable_nodes]: Loaded node '/resize_right_ess_size' in container '/foundationpose_container'
[controller_server-7] [INFO] [1748607140.387576599] [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] [launch_ros.actions.load_composable_nodes]: Loaded node '/ess_node' in container '/foundationpose_container'
[INFO] [launch_ros.actions.load_composable_nodes]: Loaded node '/disparity_to_depth' in container '/foundationpose_container'
[controller_server-7] [INFO] [1748607140.887560684] [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-7] [INFO] [1748607141.387564224] [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] [launch_ros.actions.load_composable_nodes]: Loaded node '/foundationpose_node' in container '/foundationpose_container'
[INFO] [launch_ros.actions.load_composable_nodes]: Loaded node '/selector_node' in container '/foundationpose_container'
[controller_server-7] [INFO] [1748607141.890577036] [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] [launch_ros.actions.load_composable_nodes]: Loaded node '/foundationpose_tracking_node' in container '/foundationpose_container'
[controller_server-7] [INFO] [1748607142.390571455] [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-7] [INFO] [1748607142.887561111] [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-7] [INFO] [1748607143.388651225] [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-7] [INFO] [1748607143.890575600] [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-7] [INFO] [1748607144.387564966] [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-7] [INFO] [1748607144.890573293] [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-7] [INFO] [1748607145.387562177] [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-7] [INFO] [1748607145.890584423] [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-7] [INFO] [1748607146.390575666] [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-7] [INFO] [1748607146.887711138] [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-7] [INFO] [1748607147.390701285] [local_costmap.local_costmap]: start
[controller_server-7] [INFO] [1748607147.446662294] [controller_server]: Creating bond (controller_server) to lifecycle manager.
[amcl-5] [INFO] [1748607147.554737162] [amcl]: createLaserObject
[lifecycle_manager-14] [INFO] [1748607147.560619838] [lifecycle_manager_navigation]: Server controller_server connected with bond.
[lifecycle_manager-14] [INFO] [1748607147.560704669] [lifecycle_manager_navigation]: Activating smoother_server
[smoother_server-8] [INFO] [1748607147.562648260] [smoother_server]: Activating
[smoother_server-8] [INFO] [1748607147.562739267] [smoother_server]: Creating bond (smoother_server) to lifecycle manager.
[lifecycle_manager-14] [INFO] [1748607147.669531015] [lifecycle_manager_navigation]: Server smoother_server connected with bond.
[lifecycle_manager-14] [INFO] [1748607147.669611974] [lifecycle_manager_navigation]: Activating planner_server
[planner_server-9] [INFO] [1748607147.670302493] [planner_server]: Activating
[planner_server-9] [INFO] [1748607147.670394268] [global_costmap.global_costmap]: Activating
[planner_server-9] [INFO] [1748607147.670419740] [global_costmap.global_costmap]: Checking transform
[planner_server-9] [INFO] [1748607147.670519611] [global_costmap.global_costmap]: Timed out waiting for transform from base_link to map to become available, tf error: Lookup would require extrapolation at time 0.116667, but only time 1.000000 is in the buffer, when looking up transform from frame [base_link] to frame [map]
[planner_server-9] [INFO] [1748607148.170580771] [global_costmap.global_costmap]: Timed out waiting for transform from base_link to map to become available, tf error: Lookup would require extrapolation into the past. Requested time 0.166667 but the earliest data is at time 1.000000, when looking up transform from frame [base_link] to frame [map]
[planner_server-9] [INFO] [1748607148.670552682] [global_costmap.global_costmap]: Timed out waiting for transform from base_link to map to become available, tf error: Lookup would require extrapolation into the past. Requested time 0.216667 but the earliest data is at time 1.000000, when looking up transform from frame [base_link] to frame [map]
[planner_server-9] [INFO] [1748607149.170576177] [global_costmap.global_costmap]: Timed out waiting for transform from base_link to map to become available, tf error: Lookup would require extrapolation into the past. Requested time 0.283333 but the earliest data is at time 1.000000, when looking up transform from frame [base_link] to frame [map]
[planner_server-9] [INFO] [1748607149.670779189] [global_costmap.global_costmap]: Timed out waiting for transform from base_link to map to become available, tf error: Lookup would require extrapolation into the past. Requested time 0.350000 but the earliest data is at time 1.000000, when looking up transform from frame [base_link] to frame [map]
...
[planner_server-9] [INFO] [1748607153.170576810] [global_costmap.global_costmap]: Timed out waiting for transform from base_link to map to become available, tf error: Lookup would require extrapolation into the past. Requested time 0.866667 but the earliest data is at time 1.000000, when looking up transform from frame [base_link] to frame [map]
[planner_server-9] [INFO] [1748607153.670554698] [global_costmap.global_costmap]: Timed out waiting for transform from base_link to map to become available, tf error: Lookup would require extrapolation into the past. Requested time 0.933333 but the earliest data is at time 1.000000, when looking up transform from frame [base_link] to frame [map]
[planner_server-9] [INFO] [1748607154.170689383] [global_costmap.global_costmap]: start
[planner_server-9] [INFO] [1748607155.221501683] [planner_server]: Activating plugin GridBased of type NavfnPlanner
[planner_server-9] [INFO] [1748607155.222340169] [planner_server]: Creating bond (planner_server) to lifecycle manager.
[lifecycle_manager-14] [INFO] [1748607155.325778229] [lifecycle_manager_navigation]: Server planner_server connected with bond.
[lifecycle_manager-14] [INFO] [1748607155.325871796] [lifecycle_manager_navigation]: Activating behavior_server
[behavior_server-10] [INFO] [1748607155.326384461] [behavior_server]: Activating
[behavior_server-10] [INFO] [1748607155.326450477] [behavior_server]: Activating spin
[behavior_server-10] [INFO] [1748607155.326474540] [behavior_server]: Activating backup
[behavior_server-10] [INFO] [1748607155.326490476] [behavior_server]: Activating drive_on_heading
[behavior_server-10] [INFO] [1748607155.326505100] [behavior_server]: Activating wait
[behavior_server-10] [INFO] [1748607155.326523948] [behavior_server]: Creating bond (behavior_server) to lifecycle manager.
[lifecycle_manager-14] [INFO] [1748607155.430213333] [lifecycle_manager_navigation]: Server behavior_server connected with bond.
[lifecycle_manager-14] [INFO] [1748607155.430309268] [lifecycle_manager_navigation]: Activating bt_navigator
[bt_navigator-11] [INFO] [1748607155.430789037] [bt_navigator]: Activating
[bt_navigator-11] [INFO] [1748607155.533360677] [bt_navigator]: Creating bond (bt_navigator) to lifecycle manager.
[lifecycle_manager-14] [INFO] [1748607155.640420739] [lifecycle_manager_navigation]: Server bt_navigator connected with bond.
[lifecycle_manager-14] [INFO] [1748607155.640512738] [lifecycle_manager_navigation]: Activating waypoint_follower
[waypoint_follower-12] [INFO] [1748607155.640993948] [waypoint_follower]: Activating
[waypoint_follower-12] [INFO] [1748607155.641080443] [waypoint_follower]: Creating bond (waypoint_follower) to lifecycle manager.
[lifecycle_manager-14] [INFO] [1748607155.745005089] [lifecycle_manager_navigation]: Server waypoint_follower connected with bond.
[lifecycle_manager-14] [INFO] [1748607155.745092832] [lifecycle_manager_navigation]: Activating velocity_smoother
[velocity_smoother-13] [INFO] [1748607155.745594233] [velocity_smoother]: Activating
[velocity_smoother-13] [INFO] [1748607155.745723928] [velocity_smoother]: Creating bond (velocity_smoother) to lifecycle manager.
[lifecycle_manager-14] [INFO] [1748607155.849772764] [lifecycle_manager_navigation]: Server velocity_smoother connected with bond.
[lifecycle_manager-14] [INFO] [1748607155.849856731] [lifecycle_manager_navigation]: Managed nodes are active
[lifecycle_manager-14] [INFO] [1748607155.849876667] [lifecycle_manager_navigation]: Creating bond timer...
[opennav_docking-15] [INFO] [1748607173.313717435] [docking_server]: Attempting to dock robot at charger at position (-10.00, 14.00).
[bt_navigator-11] [INFO] [1748607173.315602819] [bt_navigator]: Begin navigating from current location (-2.00, 14.00) to (-9.30, 14.00)
[controller_server-7] [INFO] [1748607173.360975416] [controller_server]: Received a goal, begin computing control effort.
[controller_server-7] [WARN] [1748607173.361090263] [controller_server]: No goal checker was specified in parameter 'current_goal_checker'. Server will use only plugin loaded goal_checker . This warning will appear once.
[controller_server-7] [ERROR] [1748607173.362834304] [tf_help]: Transform data too old when converting from odom to map
[controller_server-7] [ERROR] [1748607173.362876447] [tf_help]: Data time: 3s 33333491ns, Transform time: 1s 450031273ns
[controller_server-7] [WARN] [1748607173.363023102] [controller_server]: Unable to transform robot pose into global plan's frame
[controller_server-7] [ERROR] [1748607173.412780186] [tf_help]: Transform data too old when converting from odom to map
[controller_server-7] [ERROR] [1748607173.412831514] [tf_help]: Data time: 3s 33333491ns, Transform time: 1s 450031273ns
[controller_server-7] [WARN] [1748607173.412883129] [controller_server]: Unable to transform robot pose into global plan's frame
...
[controller_server-7] [ERROR] [1748607182.217898437] [tf_help]: Transform data too old when converting from odom to map
[controller_server-7] [ERROR] [1748607182.217945861] [tf_help]: Data time: 3s 850000200ns, Transform time: 1s 450031273ns
[controller_server-7] [WARN] [1748607182.217996164] [controller_server]: Unable to transform robot pose into global plan's frame
[controller_server-7] [ERROR] [1748607182.267837118] [tf_help]: Transform data too old when converting from odom to map
[controller_server-7] [ERROR] [1748607182.267888638] [tf_help]: Data time: 3s 850000200ns, Transform time: 1s 450031273ns
[controller_server-7] [WARN] [1748607182.267943709] [controller_server]: Unable to transform robot pose into global plan's frame
[controller_server-7] [INFO] [1748607182.318586765] [controller_server]: Passing new path to controller.
[controller_server-7] [INFO] [1748607183.367699696] [controller_server]: Passing new path to controller.
[controller_server-7] [INFO] [1748607184.417737509] [controller_server]: Passing new path to controller.
[controller_server-7] [INFO] [1748607185.467695479] [controller_server]: Passing new path to controller.
[controller_server-7] [INFO] [1748607186.517698917] [controller_server]: Passing new path to controller.
[controller_server-7] [INFO] [1748607187.569190716] [controller_server]: Passing new path to controller.
[controller_server-7] [INFO] [1748607188.618100657] [controller_server]: Passing new path to controller.
[controller_server-7] [INFO] [1748607189.717727537] [controller_server]: Passing new path to controller.
[controller_server-7] [INFO] [1748607190.767708945] [controller_server]: Passing new path to controller.
[controller_server-7] [INFO] [1748607191.819631829] [controller_server]: Passing new path to controller.
[controller_server-7] [INFO] [1748607192.867709224] [controller_server]: Passing new path to controller.
[controller_server-7] [INFO] [1748607193.917933243] [controller_server]: Passing new path to controller.
[controller_server-7] [INFO] [1748607194.967706897] [controller_server]: Passing new path to controller.
[controller_server-7] [INFO] [1748607196.067703190] [controller_server]: Passing new path to controller.
[controller_server-7] [ERROR] [1748607196.667829755] [tf_help]: Transform data too old when converting from odom to map
[controller_server-7] [ERROR] [1748607196.667881402] [tf_help]: Data time: 4s 966666925ns, Transform time: 4s 750031445ns
[controller_server-7] [WARN] [1748607196.667938842] [controller_server]: Unable to transform robot pose into global plan's frame
[controller_server-7] [ERROR] [1748607196.717814673] [tf_help]: Transform data too old when converting from odom to map
[controller_server-7] [ERROR] [1748607196.717862385] [tf_help]: Data time: 4s 966666925ns, Transform time: 4s 750031445ns
[controller_server-7] [WARN] [1748607196.717910704] [controller_server]: Unable to transform robot pose into global plan's frame
...
[controller_server-7] [ERROR] [1748607204.403659577] [tf_help]: Transform data too old when converting from odom to map
[controller_server-7] [ERROR] [1748607204.403717112] [tf_help]: Data time: 5s 400000281ns, Transform time: 4s 750031445ns
[controller_server-7] [WARN] [1748607204.403777912] [controller_server]: Unable to transform robot pose into global plan's frame
[controller_server-7] [ERROR] [1748607204.452948119] [tf_help]: Transform data too old when converting from odom to map
[controller_server-7] [ERROR] [1748607204.452995734] [tf_help]: Data time: 5s 400000281ns, Transform time: 4s 750031445ns
[controller_server-7] [WARN] [1748607204.453052406] [controller_server]: Unable to transform robot pose into global plan's frame
[controller_server-7] [INFO] [1748607204.502442258] [controller_server]: Passing new path to controller.
[controller_server-7] [ERROR] [1748607204.503205576] [tf_help]: Transform data too old when converting from odom to map
[controller_server-7] [ERROR] [1748607204.503240968] [tf_help]: Data time: 5s 533333621ns, Transform time: 4s 750031445ns
[controller_server-7] [WARN] [1748607204.503291463] [controller_server]: Unable to transform robot pose into global plan's frame
[controller_server-7] [ERROR] [1748607204.552606917] [tf_help]: Transform data too old when converting from odom to map
[controller_server-7] [ERROR] [1748607204.552654916] [tf_help]: Data time: 5s 533333621ns, Transform time: 4s 750031445ns
[controller_server-7] [WARN] [1748607204.552789699] [controller_server]: Unable to transform robot pose into global plan's frame
[controller_server-7] [ERROR] [1748607204.602618233] [tf_help]: Transform data too old when converting from odom to map
[controller_server-7] [ERROR] [1748607204.602665849] [tf_help]: Data time: 5s 533333621ns, Transform time: 4s 750031445ns
[controller_server-7] [WARN] [1748607204.602718648] [controller_server]: Unable to transform robot pose into global plan's frame
[controller_server-7] [ERROR] [1748607204.652606094] [tf_help]: Transform data too old when converting from odom to map
[controller_server-7] [ERROR] [1748607204.652654318] [tf_help]: Data time: 5s 533333621ns, Transform time: 4s 750031445ns
[controller_server-7] [WARN] [1748607204.652704173] [controller_server]: Unable to transform robot pose into global plan's frame
[controller_server-7] [ERROR] [1748607204.702628259] [tf_help]: Transform data too old when converting from odom to map
[controller_server-7] [ERROR] [1748607204.702679842] [tf_help]: Data time: 5s 533333621ns, Transform time: 4s 750031445ns
[controller_server-7] [WARN] [1748607204.702732513] [controller_server]: Unable to transform robot pose into global plan's frame
[controller_server-7] [ERROR] [1748607204.752637783] [tf_help]: Transform data too old when converting from odom to map
[controller_server-7] [ERROR] [1748607204.752688375] [tf_help]: Data time: 5s 533333621ns, Transform time: 4s 750031445ns
[controller_server-7] [WARN] [1748607204.752738998] [controller_server]: Unable to transform robot pose into global plan's frame
[controller_server-7] [ERROR] [1748607204.802656044] [tf_help]: Transform data too old when converting from odom to map
[controller_server-7] [ERROR] [1748607204.802708747] [tf_help]: Data time: 5s 533333621ns, Transform time: 4s 750031445ns
[controller_server-7] [WARN] [1748607204.802792618] [controller_server]: Unable to transform robot pose into global plan's frame
[controller_server-7] [ERROR] [1748607204.852593409] [tf_help]: Transform data too old when converting from odom to map
[controller_server-7] [ERROR] [1748607204.852639617] [tf_help]: Data time: 5s 550000289ns, Transform time: 4s 750031445ns
[controller_server-7] [WARN] [1748607204.852692416] [controller_server]: Unable to transform robot pose into global plan's frame
[controller_server-7] [ERROR] [1748607204.852750591] [controller_server]: Controller patience exceeded
[controller_server-7] [WARN] [1748607204.852870718] [controller_server]: [follow_path] [ActionServer] Aborting handle.
[behavior_server-10] [INFO] [1748607204.876589609] [behavior_server]: Running spin
[behavior_server-10] [INFO] [1748607204.876870565] [behavior_server]: Turning 1.57 for spin behavior.
[behavior_server-10] [INFO] [1748607234.477102684] [behavior_server]: spin completed successfully
[controller_server-7] [INFO] [1748607234.577101277] [controller_server]: Received a goal, begin computing control effort.
[controller_server-7] [ERROR] [1748607234.579217057] [tf_help]: Transform data too old when converting from odom to map
[controller_server-7] [ERROR] [1748607234.580362226] [tf_help]: Data time: 7s 683333734ns, Transform time: 6s 950031560ns
[controller_server-7] [WARN] [1748607234.581593794] [controller_server]: Unable to transform robot pose into global plan's frame
[controller_server-7] [ERROR] [1748607234.629261777] [tf_help]: Transform data too old when converting from odom to map
[controller_server-7] [ERROR] [1748607234.630680126] [tf_help]: Data time: 7s 683333734ns, Transform time: 6s 950031560ns
[controller_server-7] [WARN] [1748607234.631680241] [controller_server]: Unable to transform robot pose into global plan's frame
...
[controller_server-7] [ERROR] [1748607238.579237381] [tf_help]: Transform data too old when converting from odom to map
[controller_server-7] [ERROR] [1748607238.579286053] [tf_help]: Data time: 7s 883333744ns, Transform time: 6s 950031560ns
[controller_server-7] [WARN] [1748607238.579339652] [controller_server]: Unable to transform robot pose into global plan's frame
[controller_server-7] [ERROR] [1748607238.629256949] [tf_help]: Transform data too old when converting from odom to map
[controller_server-7] [ERROR] [1748607238.629305044] [tf_help]: Data time: 7s 883333744ns, Transform time: 6s 950031560ns
[controller_server-7] [WARN] [1748607238.629357331] [controller_server]: Unable to transform robot pose into global plan's frame
[controller_server-7] [ERROR] [1748607238.629412051] [controller_server]: Controller patience exceeded
[controller_server-7] [WARN] [1748607238.629475922] [controller_server]: [follow_path] [ActionServer] Aborting handle.
[controller_server-7] [INFO] [1748607238.656238963] [local_costmap.local_costmap]: Received request to clear entirely the local_costmap
[controller_server-7] [INFO] [1748607238.657773886] [controller_server]: Received a goal, begin computing control effort.
[controller_server-7] [INFO] [1748607238.798050029] [controller_server]: Passing new path to controller.
[controller_server-7] [ERROR] [1748607238.798576742] [tf_help]: Transform data too old when converting from odom to map
[controller_server-7] [ERROR] [1748607238.798612294] [tf_help]: Data time: 7s 883333744ns, Transform time: 6s 950031560ns
[controller_server-7] [WARN] [1748607238.798659365] [controller_server]: Unable to transform robot pose into global plan's frame
[controller_server-7] [WARN] [1748607238.798828739] [controller_server]: Control loop missed its desired rate of 20.0000Hz
[controller_server-7] [ERROR] [1748607238.798911586] [tf_help]: Transform data too old when converting from odom to map
[controller_server-7] [ERROR] [1748607238.798921474] [tf_help]: Data time: 7s 883333744ns, Transform time: 6s 950031560ns
[controller_server-7] [WARN] [1748607238.798952034] [controller_server]: Unable to transform robot pose into global plan's frame
Screenshots or Videos
(If applicable, add screenshots or links to videos that demonstrate the issue)
Additional Information
What I’ve Tried
(Describe any troubleshooting steps you’ve already taken)
I’ve also checked the RTF, and it was about 1.
Related Issues
(If you’re aware of any related issues or forum posts, please link them here)
Additional Context
(Add any other context about the problem here)