nav2 troubles all over the place!! Please help (if you can!) :-)
Hello,
I am trying to use nav2 on a real robot, which is running Foxy. The robot hardware and sensors and ROS2 controllers start and run with no problems 95% of the time.
However, nav2 starts and runs 5% of the time, so that I can run SLAM and navigate the robot and map the environment. The rest of 95%, some random thing prevents nav2 from running.
I have included my launch file at the end. But, I am describing the problems first. Here are the problems that randomly arise when I am trying to start nav2. Note that at each trial, the problem is different.
I have the following topics that are published correctly:
prompt$ ros2 topic list
/cmd_vel
/diagnostics
/diffbot_base_controller/cmd_vel_unstamped
/dynamic_joint_states
/forward_position_controller/commands
/imu
/joint_states
/joy
/joy/set_feedback
/left/camera_info
/left/image_rect
/motor_control
/motor_status
/odom
/odometry/filtered
/parameter_events
/right/camera_info
/right/image_rect
/robot_description
/rosout
/scan
/set_pose
/stereo/camera_info
/stereo/converted_depth
/stereo/depth
/stereo/points
/tf
/tf_static
Problem type 1: slam_toolbox cannot register the Lidar.
When I bringup nav2 using my launch file, here is what I get:
prompt$ ros2 launch robot_user_robot_nav nav2_bringup_tb3_revised_launch.py slam:=True
[INFO] [launch]: All log files can be found below /home/robot_user/.ros/log/2023-06-27-15-16-54-669455-robot_user-Xavier-19352
[INFO] [launch]: Default logging verbosity is set to INFO
[INFO] [sync_slam_toolbox_node-1]: process started with pid [19354]
[INFO] [map_saver_server-2]: process started with pid [19356]
[INFO] [lifecycle_manager-3]: process started with pid [19358]
[INFO] [controller_server-4]: process started with pid [19360]
[INFO] [planner_server-5]: process started with pid [19362]
[INFO] [recoveries_server-6]: process started with pid [19364]
[INFO] [bt_navigator-7]: process started with pid [19366]
[INFO] [waypoint_follower-8]: process started with pid [19368]
[INFO] [lifecycle_manager-9]: process started with pid [19377]
[lifecycle_manager-3] [INFO] [1687897016.045531301] [lifecycle_manager_slam]: Creating
[lifecycle_manager-3] [INFO] [1687897016.079812558] [lifecycle_manager_slam]: Creating and initializing lifecycle service clients
[lifecycle_manager-3] [INFO] [1687897016.153660836] [lifecycle_manager_slam]: Starting managed nodes bringup...
[lifecycle_manager-3] [INFO] [1687897016.153758984] [lifecycle_manager_slam]: Configuring map_saver
[bt_navigator-7] [INFO] [1687897016.290348085] [bt_navigator]:
[bt_navigator-7] bt_navigator lifecycle node launched.
[bt_navigator-7] Waiting on external lifecycle transitions to activate
[bt_navigator-7] See https://design.ros2.org/articles/node_lifecycle.html for more information.
[bt_navigator-7] [INFO] [1687897016.290661730] [bt_navigator]: Creating
[planner_server-5] [INFO] [1687897016.328064562] [planner_server]:
[planner_server-5] planner_server lifecycle node launched.
[planner_server-5] Waiting on external lifecycle transitions to activate
[planner_server-5] See https://design.ros2.org/articles/node_lifecycle.html for more information.
[planner_server-5] [INFO] [1687897016.331484742] [planner_server]: Creating
[recoveries_server-6] [INFO] [1687897016.527387413] [recoveries_server]:
[recoveries_server-6] recoveries_server lifecycle node launched.
[recoveries_server-6] Waiting on external lifecycle transitions to activate
[recoveries_server-6] See https://design.ros2.org/articles/node_lifecycle.html for more information.
[map_saver_server-2] [INFO] [1687897016.592736828] [map_saver]:
[map_saver_server-2] map_saver lifecycle node launched.
[map_saver_server-2] Waiting on external lifecycle transitions to activate
[map_saver_server-2] See https://design.ros2.org/articles/node_lifecycle.html for more information.
[map_saver_server-2] [INFO] [1687897016.592960133] [map_saver]: Creating
[lifecycle_manager-9] [INFO] [1687897016.618960328] [lifecycle_manager_navigation]: Creating
[sync_slam_toolbox_node-1] [INFO] [1687897016.675506131] [slam_toolbox]: Node using stack size 160000000
[controller_server-4] [INFO] [1687897016.693737191] [controller_server]:
[controller_server-4] controller_server lifecycle node launched.
[controller_server-4] Waiting on external lifecycle transitions to activate
[controller_server-4] See https://design.ros2.org/articles/node_lifecycle.html for more information.
[map_saver_server-2] [INFO] [1687897016.718958248] [map_saver]: Configuring
[controller_server-4] [INFO] [1687897016.732853920] [controller_server]: Creating controller server
[lifecycle_manager-9] [INFO] [1687897016.748402528] [lifecycle_manager_navigation]: Creating and initializing lifecycle service clients
[lifecycle_manager-3] [INFO] [1687897016.753079978] [lifecycle_manager_slam]: Activating map_saver
[map_saver_server-2] [INFO] [1687897016.754003890] [map_saver]: Activating
[lifecycle_manager-3] [INFO] [1687897016.760864026] [lifecycle_manager_slam]: Managed nodes are active
[waypoint_follower-8] [INFO] [1687897016.831196249] [waypoint_follower]:
[waypoint_follower-8] waypoint_follower lifecycle node launched.
[waypoint_follower-8] Waiting on external lifecycle transitions to activate
[waypoint_follower-8] See https://design.ros2.org/articles/node_lifecycle.html for more information.
[waypoint_follower-8] [INFO] [1687897016.831466404] [waypoint_follower]: Creating
[planner_server-5] [INFO] [1687897016.850412439] [global_costmap.global_costmap]:
[planner_server-5] global_costmap lifecycle node launched.
[planner_server-5] Waiting on external lifecycle transitions to activate
[planner_server-5] See https://design.ros2.org/articles/node_lifecycle.html for more information.
[planner_server-5] [INFO] [1687897016.855930949] [global_costmap.global_costmap]: Creating Costmap
[lifecycle_manager-9] [INFO] [1687897016.867657504] [lifecycle_manager_navigation]: Starting managed nodes bringup...
[lifecycle_manager-9] [INFO] [1687897016.867764836] [lifecycle_manager_navigation]: Configuring controller_server
[controller_server-4] [INFO] [1687897016.951899319] [local_costmap.local_costmap]:
[controller_server-4] local_costmap lifecycle node launched.
[controller_server-4] Waiting on external lifecycle transitions to activate
[controller_server-4] See https://design.ros2.org/articles/node_lifecycle.html for more information.
[controller_server-4] [INFO] [1687897016.953258706] [local_costmap.local_costmap]: Creating Costmap
[sync_slam_toolbox_node-1] [INFO] [1687897017.235519543] [slam_toolbox]: Using solver plugin solver_plugins::CeresSolver
[sync_slam_toolbox_node-1] [INFO] [1687897017.244129163] [slam_toolbox]: CeresSolver: Using SCHUR_JACOBI preconditioner.
[sync_slam_toolbox_node-1] [INFO] [1687897017.377671990] [slam_toolbox]: Message Filter dropping message: frame 'scan_link' at time 1687897017.224 for reason 'Unknown'
[sync_slam_toolbox_node-1] Registering sensor: [Custom Described Lidar]
And the process just hangs there!
While this is hanging, I can echo the /scan topic:
prompt$ ros2 topic echo /scan
header:
stamp:
sec: 1687897075
nanosec: 121530994
frame_id: scan_link
angle_min: -3.1241390705108643
angle_max: 3.1415927410125732
angle_increment: 0.0034828970674425364
time_increment: 4.405255094752647e-05
scan_time: 0.07925054430961609
range_min: 0.15000000596046448
range_max: 25.0
ranges:
- 5.1519999504089355
- 5.168000221252441
- 5.159999847412109
- 5.159999847412109
- 5.159999847412109
- '...'
intensities:
- 47.0
- 47.0
- 47.0
- 47.0
- 47.0
- 47.0
- '...'
Why does slam_toolbox fail to register the Lidar?
Problem type 2: Sometimes, problem 1 does not occur, but "Robot is out of bounds of the costmap!"
prompt$ ros2 launch robot_user_robot_nav nav2_bringup_tb3_revised_launch.py slam:=True
[INFO] [launch]: All log files can be found below /home/robot_user/.ros/log/2023-06-27-15-18-57-783715-robot_user-Xavier-19586
[INFO] [launch]: Default logging verbosity is set to INFO
[INFO] [sync_slam_toolbox_node-1]: process started with pid [19588]
[INFO] [map_saver_server-2]: process started with pid [19590]
[INFO] [lifecycle_manager-3]: process started with pid [19592]
[INFO] [controller_server-4]: process started with pid [19594]
[INFO] [planner_server-5]: process started with pid [19596]
[INFO] [recoveries_server-6]: process started with pid [19598]
[INFO] [bt_navigator-7]: process started with pid [19600]
[INFO] [waypoint_follower-8]: process started with pid [19603]
[INFO] [lifecycle_manager-9]: process started with pid [19610]
[lifecycle_manager-3] [INFO] [1687897139.134543996] [lifecycle_manager_slam]: Creating
[lifecycle_manager-3] [INFO] [1687897139.190958031] [lifecycle_manager_slam]: Creating and initializing lifecycle service clients
[lifecycle_manager-3] [INFO] [1687897139.200955314] [lifecycle_manager_slam]: Starting managed nodes bringup...
[lifecycle_manager-3] [INFO] [1687897139.201073239] [lifecycle_manager_slam]: Configuring map_saver
[planner_server-5] [INFO] [1687897139.246887947] [planner_server]:
[planner_server-5] planner_server lifecycle node launched.
[planner_server-5] Waiting on external lifecycle transitions to activate
[planner_server-5] See https://design.ros2.org/articles/node_lifecycle.html for more information.
[planner_server-5] [INFO] [1687897139.255689688] [planner_server]: Creating
[controller_server-4] [INFO] [1687897139.337417281] [controller_server]:
[controller_server-4] controller_server lifecycle node launched.
[controller_server-4] Waiting on external lifecycle transitions to activate
[controller_server-4] See https://design.ros2.org/articles/node_lifecycle.html for more information.
[controller_server-4] [INFO] [1687897139.380093063] [controller_server]: Creating controller server
[waypoint_follower-8] [INFO] [1687897139.548893418] [waypoint_follower]:
[waypoint_follower-8] waypoint_follower lifecycle node launched.
[waypoint_follower-8] Waiting on external lifecycle transitions to activate
[waypoint_follower-8] See https://design.ros2.org/articles/node_lifecycle.html for more information.
[waypoint_follower-8] [INFO] [1687897139.549124981] [waypoint_follower]: Creating
[planner_server-5] [INFO] [1687897139.585534496] [global_costmap.global_costmap]:
[planner_server-5] global_costmap lifecycle node launched.
[planner_server-5] Waiting on external lifecycle transitions to activate
[planner_server-5] See https://design.ros2.org/articles/node_lifecycle.html for more information.
[planner_server-5] [INFO] [1687897139.590343129] [global_costmap.global_costmap]: Creating Costmap
[map_saver_server-2] [INFO] [1687897139.602973395] [map_saver]:
[map_saver_server-2] map_saver lifecycle node launched.
[map_saver_server-2] Waiting on external lifecycle transitions to activate
[map_saver_server-2] See https://design.ros2.org/articles/node_lifecycle.html for more information.
[map_saver_server-2] [INFO] [1687897139.604740483] [map_saver]: Creating
[controller_server-4] [INFO] [1687897139.630518926] [local_costmap.local_costmap]:
[controller_server-4] local_costmap lifecycle node launched.
[controller_server-4] Waiting on external lifecycle transitions to activate
[controller_server-4] See https://design.ros2.org/articles/node_lifecycle.html for more information.
[controller_server-4] [INFO] [1687897139.640325737] [local_costmap.local_costmap]: Creating Costmap
[sync_slam_toolbox_node-1] [INFO] [1687897139.725643252] [slam_toolbox]: Node using stack size 160000000
[lifecycle_manager-9] [INFO] [1687897139.745089249] [lifecycle_manager_navigation]: Creating
[bt_navigator-7] [INFO] [1687897139.815001077] [bt_navigator]:
[bt_navigator-7] bt_navigator lifecycle node launched.
[bt_navigator-7] Waiting on external lifecycle transitions to activate
[bt_navigator-7] See https://design.ros2.org/articles/node_lifecycle.html for more information.
[bt_navigator-7] [INFO] [1687897139.815314723] [bt_navigator]: Creating
[recoveries_server-6] [INFO] [1687897139.829431360] [recoveries_server]:
[recoveries_server-6] recoveries_server lifecycle node launched.
[recoveries_server-6] Waiting on external lifecycle transitions to activate
[recoveries_server-6] See https://design.ros2.org/articles/node_lifecycle.html for more information.
[map_saver_server-2] [INFO] [1687897139.836010313] [map_saver]: Configuring
[lifecycle_manager-3] [INFO] [1687897139.857410223] [lifecycle_manager_slam]: Activating map_saver
[map_saver_server-2] [INFO] [1687897139.858068845] [map_saver]: Activating
[lifecycle_manager-3] [INFO] [1687897139.859654868] [lifecycle_manager_slam]: Managed nodes are active
[lifecycle_manager-9] [INFO] [1687897139.875036395] [lifecycle_manager_navigation]: Creating and initializing lifecycle service clients
[lifecycle_manager-9] [INFO] [1687897139.948133550] [lifecycle_manager_navigation]: Starting managed nodes bringup...
[lifecycle_manager-9] [INFO] [1687897139.948229138] [lifecycle_manager_navigation]: Configuring controller_server
[controller_server-4] [INFO] [1687897140.051695409] [controller_server]: Configuring controller interface
[controller_server-4] [INFO] [1687897140.052987723] [controller_server]: Controller frequency set to 2.0000Hz
[controller_server-4] [INFO] [1687897140.053074799] [local_costmap.local_costmap]: Configuring
[controller_server-4] [INFO] [1687897140.080115988] [local_costmap.local_costmap]: Using plugin "inflation_layer"
[controller_server-4] [INFO] [1687897140.095260448] [local_costmap.local_costmap]: Initialized plugin "inflation_layer"
[controller_server-4] [INFO] [1687897140.095368165] [local_costmap.local_costmap]: Using plugin "voxel_layer"
[controller_server-4] [INFO] [1687897140.097351358] [local_costmap.local_costmap]: Subscribed to Topics: pointcloud scan
[sync_slam_toolbox_node-1] [INFO] [1687897140.098771038] [slam_toolbox]: Using solver plugin solver_plugins::CeresSolver
[sync_slam_toolbox_node-1] [INFO] [1687897140.099877040] [slam_toolbox]: CeresSolver: Using SCHUR_JACOBI preconditioner.
[controller_server-4] [INFO] [1687897140.168363620] [local_costmap.local_costmap]: Initialized plugin "voxel_layer"
[controller_server-4] [INFO] [1687897140.204377278] [controller_server]: Created progress_checker : progress_checker of type nav2_controller::SimpleProgressChecker
[controller_server-4] [INFO] [1687897140.206421754] [controller_server]: Created goal_checker : goal_checker of type nav2_controller::SimpleGoalChecker
[controller_server-4] [INFO] [1687897140.214638605] [controller_server]: Created controller : FollowPath of type dwb_core::DWBLocalPlanner
[controller_server-4] [INFO] [1687897140.218874317] [controller_server]: Setting transform_tolerance to 1.000000
[controller_server-4] [INFO] [1687897140.286537052] [controller_server]: Using critic "RotateToGoal" (dwb_critics::RotateToGoalCritic)
[controller_server-4] [INFO] [1687897140.289527043] [controller_server]: Critic plugin initialized
[controller_server-4] [INFO] [1687897140.290197601] [controller_server]: Using critic "Oscillation" (dwb_critics::OscillationCritic)
[controller_server-4] [INFO] [1687897140.292795062] [controller_server]: Critic plugin initialized
[controller_server-4] [INFO] [1687897140.293489077] [controller_server]: Using critic "BaseObstacle" (dwb_critics::BaseObstacleCritic)
[controller_server-4] [INFO] [1687897140.294741326] [controller_server]: Critic plugin initialized
[controller_server-4] [INFO] [1687897140.295715866] [controller_server]: Using critic "GoalAlign" (dwb_critics::GoalAlignCritic)
[controller_server-4] [INFO] [1687897140.298691168] [controller_server]: Critic plugin initialized
[controller_server-4] [INFO] [1687897140.300482193] [controller_server]: Using critic "PathAlign" (dwb_critics::PathAlignCritic)
[controller_server-4] [INFO] [1687897140.303283120] [controller_server]: Critic plugin initialized
[controller_server-4] [INFO] [1687897140.305469266] [controller_server]: Using critic "PathDist" (dwb_critics::PathDistCritic)
[controller_server-4] [INFO] [1687897140.307687126] [controller_server]: Critic plugin initialized
[controller_server-4] [INFO] [1687897140.308854411] [controller_server]: Using critic "GoalDist" (dwb_critics::GoalDistCritic)
[controller_server-4] [INFO] [1687897140.310029728] [controller_server]: Critic plugin initialized
[controller_server-4] [INFO] [1687897140.310151878] [controller_server]: Controller Server has FollowPath controllers available.
[lifecycle_manager-9] [INFO] [1687897140.334220836] [lifecycle_manager_navigation]: Configuring planner_server
[planner_server-5] [INFO] [1687897140.335150062] [planner_server]: Configuring
[planner_server-5] [INFO] [1687897140.335239154] [global_costmap.global_costmap]: Configuring
[planner_server-5] [INFO] [1687897140.351435342] [global_costmap.global_costmap]: Using plugin "static_layer"
[planner_server-5] [INFO] [1687897140.362268599] [global_costmap.global_costmap]: Subscribing to the map topic (/map) with transient local durability
[planner_server-5] [INFO] [1687897140.366845701] [global_costmap.global_costmap]: Subscribing to updates
[planner_server-5] [INFO] [1687897140.371191338] [global_costmap.global_costmap]: Initialized plugin "static_layer"
[planner_server-5] [INFO] [1687897140.371285294] [global_costmap.global_costmap]: Using plugin "obstacle_layer"
[planner_server-5] [INFO] [1687897140.373687834] [global_costmap.global_costmap]: Subscribed to Topics: pointcloud scan
[planner_server-5] [INFO] [1687897140.404667345] [global_costmap.global_costmap]: Initialized plugin "obstacle_layer"
[planner_server-5] [INFO] [1687897140.404758485] [global_costmap.global_costmap]: Using plugin "inflation_layer"
[planner_server-5] [INFO] [1687897140.409882268] [global_costmap.global_costmap]: Initialized plugin "inflation_layer"
[planner_server-5] [INFO] [1687897140.449771109] [planner_server]: Created global planner plugin GridBased of type nav2_navfn_planner/NavfnPlanner
[planner_server-5] [INFO] [1687897140.449870762] [planner_server]: Configuring plugin GridBased of type NavfnPlanner
[planner_server-5] [INFO] [1687897140.482784984] [planner_server]: Planner Server has GridBased planners available.
[lifecycle_manager-9] [INFO] [1687897140.505425494] [lifecycle_manager_navigation]: Configuring recoveries_server
[recoveries_server-6] [INFO] [1687897140.506297373] [recoveries_server]: Configuring
[recoveries_server-6] [INFO] [1687897140.528463398] [recoveries_server]: Creating recovery plugin spin of type nav2_recoveries/Spin
[recoveries_server-6] [INFO] [1687897140.531548690] [recoveries_server]: Configuring spin
[recoveries_server-6] [INFO] [1687897140.561212717] [recoveries_server]: Creating recovery plugin back_up of type nav2_recoveries/BackUp
[recoveries_server-6] [INFO] [1687897140.563568119] [recoveries_server]: Configuring back_up
[recoveries_server-6] [INFO] [1687897140.589553676] [recoveries_server]: Creating recovery plugin wait of type nav2_recoveries/Wait
[recoveries_server-6] [INFO] [1687897140.592152482] [recoveries_server]: Configuring wait
[lifecycle_manager-9] [INFO] [1687897140.617469017] [lifecycle_manager_navigation]: Configuring bt_navigator
[bt_navigator-7] [INFO] [1687897140.618164952] [bt_navigator]: Configuring
[bt_navigator-7] [INFO] [1687897140.752719987] [bt_navigator_rclcpp_node]: Waiting for "compute_path_to_pose" action server
[bt_navigator-7] [INFO] [1687897140.753224010] [bt_navigator_rclcpp_node]: "ComputePathToPose" BtActionNode initialized
[bt_navigator-7] [INFO] [1687897140.756789163] [bt_navigator_rclcpp_node]: Waiting for "global_costmap/clear_entirely_global_costmap" service
[bt_navigator-7] [INFO] [1687897140.757116762] [bt_navigator_rclcpp_node]: "ClearGlobalCostmap-Context" BtServiceNode initialized
[bt_navigator-7] [INFO] [1687897140.777882691] [bt_navigator_rclcpp_node]: Waiting for "follow_path" action server
[bt_navigator-7] [INFO] [1687897140.778315351] [bt_navigator_rclcpp_node]: "FollowPath" BtActionNode initialized
[bt_navigator-7] [INFO] [1687897140.782660987] [bt_navigator_rclcpp_node]: Waiting for "local_costmap/clear_entirely_local_costmap" service
[bt_navigator-7] [INFO] [1687897140.782988522] [bt_navigator_rclcpp_node]: "ClearLocalCostmap-Context" BtServiceNode initialized
[bt_navigator-7] [INFO] [1687897140.786991903] [bt_navigator_rclcpp_node]: Waiting for "local_costmap/clear_entirely_local_costmap" service
[bt_navigator-7] [INFO] [1687897140.787312813] [bt_navigator_rclcpp_node]: "ClearLocalCostmap-Subtree" BtServiceNode initialized
[bt_navigator-7] [INFO] [1687897140.789894050] [bt_navigator_rclcpp_node]: Waiting for "global_costmap/clear_entirely_global_costmap" service
[bt_navigator-7] [INFO] [1687897140.790238897] [bt_navigator_rclcpp_node]: "ClearGlobalCostmap-Subtree" BtServiceNode initialized
[bt_navigator-7] [INFO] [1687897140.802984433] [bt_navigator_rclcpp_node]: Waiting for "spin" action server
[bt_navigator-7] [INFO] [1687897140.803586988] [bt_navigator_rclcpp_node]: "Spin" BtActionNode initialized
[bt_navigator-7] [INFO] [1687897140.818735224] [bt_navigator_rclcpp_node]: Waiting for "wait" action server
[bt_navigator-7] [INFO] [1687897140.819273552] [bt_navigator_rclcpp_node]: "Wait" BtActionNode initialized
[lifecycle_manager-9] [INFO] [1687897140.823771579] [lifecycle_manager_navigation]: Configuring waypoint_follower
[waypoint_follower-8] [INFO] [1687897140.824494844] [waypoint_follower]: Configuring
[lifecycle_manager-9] [INFO] [1687897140.916742817] [lifecycle_manager_navigation]: Activating controller_server
[controller_server-4] [INFO] [1687897140.917255160] [controller_server]: Activating
[controller_server-4] [INFO] [1687897140.917326523] [local_costmap.local_costmap]: Activating
[controller_server-4] [INFO] [1687897140.917359100] [local_costmap.local_costmap]: Checking transform
[controller_server-4] [INFO] [1687897140.917622664] [local_costmap.local_costmap]: start
[lifecycle_manager-9] [INFO] [1687897140.923538131] [lifecycle_manager_navigation]: Activating planner_server
[planner_server-5] [INFO] [1687897140.924126574] [planner_server]: Activating
[planner_server-5] [INFO] [1687897140.924234803] [global_costmap.global_costmap]: Activating
[planner_server-5] [INFO] [1687897140.924274645] [global_costmap.global_costmap]: Checking transform
[planner_server-5] [INFO] [1687897140.924429692] [global_costmap.global_costmap]: Timed out waiting for transform from base_footprint to map to become available, tf error: Lookup would require extrapolation into the past. Requested time 1687897140.903292 but the earliest data is at time 1687897141.350383, when looking up transform from frame [base_footprint] to frame [map]
[planner_server-5] [INFO] [1687897141.424728125] [global_costmap.global_costmap]: start
[planner_server-5] [WARN] [1687897141.425160465] [nav2_costmap_2d]: Robot is out of bounds of the costmap!
[planner_server-5] [INFO] [1687897141.436420686] [planner_server]: Activating plugin GridBased of type NavfnPlanner
[lifecycle_manager-9] [INFO] [1687897141.437519999] [lifecycle_manager_navigation]: Activating recoveries_server
[recoveries_server-6] [INFO] [1687897141.437989204] [recoveries_server]: Activating
[recoveries_server-6] [INFO] [1687897141.438071256] [recoveries_server]: Activating spin
[recoveries_server-6] [INFO] [1687897141.438101017] [recoveries_server]: Activating back_up
[recoveries_server-6] [INFO] [1687897141.438123386] [recoveries_server]: Activating wait
[lifecycle_manager-9] [INFO] [1687897141.438883005] [lifecycle_manager_navigation]: Activating bt_navigator
[bt_navigator-7] [INFO] [1687897141.439277263] [bt_navigator]: Activating
[lifecycle_manager-9] [INFO] [1687897141.440219929] [lifecycle_manager_navigation]: Activating waypoint_follower
[waypoint_follower-8] [INFO] [1687897141.440617419] [waypoint_follower]: Activating
[lifecycle_manager-9] [INFO] [1687897141.441615032] [lifecycle_manager_navigation]: Managed nodes are active
[planner_server-5] [WARN] [1687897142.424945048] [nav2_costmap_2d]: Robot is out of bounds of the costmap!
[planner_server-5] [WARN] [1687897142.425189155] [global_costmap.global_costmap]: Sensor origin at (0.01, -0.00) is out of map bounds. The costmap cannot raytrace for it.
[planner_server-5] [WARN] [1687897143.425006937] [nav2_costmap_2d]: Robot is out of bounds of the costmap!
[planner_server-5] [WARN] [1687897143.432710133] [global_costmap.global_costmap]: Sensor origin at (0.12, -0.04) is out of map bounds. The costmap cannot raytrace for it.
[planner_server-5] [WARN] [1687897143.434937850] [global_costmap.global_costmap]: Sensor origin at (0.01, -0.00) is out of map bounds. The costmap cannot raytrace for it.
[planner_server-5] [WARN] [1687897144.424978276] [nav2_costmap_2d]: Robot is out of bounds of the costmap!
[planner_server-5] [WARN] [1687897144.425660835] [global_costmap.global_costmap]: Sensor origin at (0.12, -0.04) is out of map bounds. The costmap cannot raytrace for it.
[planner_server-5] [WARN] [1687897144.425808010] [global_costmap.global_costmap]: Sensor origin at (0.01, -0.00) is out of map bounds. The costmap cannot raytrace for it.
[planner_server-5] [WARN] [1687897145.424987679] [nav2_costmap_2d]: Robot is out of bounds of the costmap!
[planner_server-5] [WARN] [1687897145.425713503] [global_costmap.global_costmap]: Sensor origin at (0.12, -0.04) is out of map bounds. The costmap cannot raytrace for it.
[planner_server-5] [WARN] [1687897145.425849093] [global_costmap.global_costmap]: Sensor origin at (0.01, -0.00) is out of map bounds. The costmap cannot raytrace for it.
[planner_server-5] [WARN] [1687897146.424934052] [nav2_costmap_2d]: Robot is out of bounds of the costmap!
What could be causing this?
Problem type 3: nav2 can't get past controller server!
prompt$ ros2 launch robot_user_robot_nav nav2_bringup_tb3_revised_launch.py slam:=True
[INFO] [launch]: All log files can be found below /home/robot_user/.ros/log/2023-06-27-15-22-59-824383-robot_user-Xavier-19852
[INFO] [launch]: Default logging verbosity is set to INFO
[INFO] [sync_slam_toolbox_node-1]: process started with pid [19854]
[INFO] [map_saver_server-2]: process started with pid [19856]
[INFO] [lifecycle_manager-3]: process started with pid [19858]
[INFO] [controller_server-4]: process started with pid [19860]
[INFO] [planner_server-5]: process started with pid [19862]
[INFO] [recoveries_server-6]: process started with pid [19864]
[INFO] [bt_navigator-7]: process started with pid [19866]
[INFO] [waypoint_follower-8]: process started with pid [19871]
[INFO] [lifecycle_manager-9]: process started with pid [19896]
[lifecycle_manager-3] [INFO] [1687897381.342701216] [lifecycle_manager_slam]: Creating
[lifecycle_manager-3] [INFO] [1687897381.376440493] [lifecycle_manager_slam]: Creating and initializing lifecycle service clients
[lifecycle_manager-3] [INFO] [1687897381.379273365] [lifecycle_manager_slam]: Starting managed nodes bringup...
[lifecycle_manager-3] [INFO] [1687897381.379352441] [lifecycle_manager_slam]: Configuring map_saver
[planner_server-5] [INFO] [1687897381.422889083] [planner_server]:
[planner_server-5] planner_server lifecycle node launched.
[planner_server-5] Waiting on external lifecycle transitions to activate
[planner_server-5] See https://design.ros2.org/articles/node_lifecycle.html for more information.
[planner_server-5] [INFO] [1687897381.431243370] [planner_server]: Creating
[map_saver_server-2] [INFO] [1687897381.552689402] [map_saver]:
[map_saver_server-2] map_saver lifecycle node launched.
[map_saver_server-2] Waiting on external lifecycle transitions to activate
[map_saver_server-2] See https://design.ros2.org/articles/node_lifecycle.html for more information.
[map_saver_server-2] [INFO] [1687897381.553056107] [map_saver]: Creating
[map_saver_server-2] [INFO] [1687897381.555491296] [map_saver]: Configuring
[lifecycle_manager-3] [INFO] [1687897381.583026884] [lifecycle_manager_slam]: Activating map_saver
[map_saver_server-2] [INFO] [1687897381.583567454] [map_saver]: Activating
[lifecycle_manager-3] [INFO] [1687897381.589391573] [lifecycle_manager_slam]: Managed nodes are active
[sync_slam_toolbox_node-1] [INFO] [1687897381.611948812] [slam_toolbox]: Node using stack size 160000000
[controller_server-4] [INFO] [1687897381.615069089] [controller_server]:
[controller_server-4] controller_server lifecycle node launched.
[controller_server-4] Waiting on external lifecycle transitions to activate
[controller_server-4] See https://design.ros2.org/articles/node_lifecycle.html for more information.
[recoveries_server-6] [INFO] [1687897381.626139954] [recoveries_server]:
[recoveries_server-6] recoveries_server lifecycle node launched.
[recoveries_server-6] Waiting on external lifecycle transitions to activate
[recoveries_server-6] See https://design.ros2.org/articles/node_lifecycle.html for more information.
[controller_server-4] [INFO] [1687897381.675447976] [controller_server]: Creating controller server
[planner_server-5] [INFO] [1687897381.702627452] [global_costmap.global_costmap]:
[planner_server-5] global_costmap lifecycle node launched.
[planner_server-5] Waiting on external lifecycle transitions to activate
[planner_server-5] See https://design.ros2.org/articles/node_lifecycle.html for more information.
[planner_server-5] [INFO] [1687897381.706712639] [global_costmap.global_costmap]: Creating Costmap
[bt_navigator-7] [INFO] [1687897381.754409256] [bt_navigator]:
[bt_navigator-7] bt_navigator lifecycle node launched.
[bt_navigator-7] Waiting on external lifecycle transitions to activate
[bt_navigator-7] See https://design.ros2.org/articles/node_lifecycle.html for more information.
[bt_navigator-7] [INFO] [1687897381.769568189] [bt_navigator]: Creating
[lifecycle_manager-9] [INFO] [1687897381.863429733] [lifecycle_manager_navigation]: Creating
[controller_server-4] [INFO] [1687897381.921688519] [local_costmap.local_costmap]:
[controller_server-4] local_costmap lifecycle node launched.
[controller_server-4] Waiting on external lifecycle transitions to activate
[controller_server-4] See https://design.ros2.org/articles/node_lifecycle.html for more information.
[controller_server-4] [INFO] [1687897381.923120940] [local_costmap.local_costmap]: Creating Costmap
[lifecycle_manager-9] [INFO] [1687897381.937751239] [lifecycle_manager_navigation]: Creating and initializing lifecycle service clients
[sync_slam_toolbox_node-1] [INFO] [1687897381.957453910] [slam_toolbox]: Using solver plugin solver_plugins::CeresSolver
[sync_slam_toolbox_node-1] [INFO] [1687897381.969938443] [slam_toolbox]: CeresSolver: Using SCHUR_JACOBI preconditioner.
[waypoint_follower-8] [INFO] [1687897381.987167779] [waypoint_follower]:
[waypoint_follower-8] waypoint_follower lifecycle node launched.
[waypoint_follower-8] Waiting on external lifecycle transitions to activate
[waypoint_follower-8] See https://design.ros2.org/articles/node_lifecycle.html for more information.
[waypoint_follower-8] [INFO] [1687897381.987436239] [waypoint_follower]: Creating
[lifecycle_manager-9] [INFO] [1687897382.020539807] [lifecycle_manager_navigation]: Starting managed nodes bringup...
[lifecycle_manager-9] [INFO] [1687897382.020642499] [lifecycle_manager_navigation]: Configuring controller_server
Why is this happening? Any ideas?
Problem type 4: nav2 just sits there timing out waiting for transforms forever!
prompt$ ros2 launch robot_user_robot_nav nav2_bringup_tb3_revised_launch.py slam:=True
[INFO] [launch]: All log files can be found below /home/robot_user/.ros/log/2023-06-27-15-24-35-448924-robot_user-Xavier-20100
[INFO] [launch]: Default logging verbosity is set to INFO
[INFO] [sync_slam_toolbox_node-1]: process started with pid [20102]
[INFO] [map_saver_server-2]: process started with pid [20104]
[INFO] [lifecycle_manager-3]: process started with pid [20106]
[INFO] [controller_server-4]: process started with pid [20108]
[INFO] [planner_server-5]: process started with pid [20110]
[INFO] [recoveries_server-6]: process started with pid [20112]
[INFO] [bt_navigator-7]: process started with pid [20114]
[INFO] [waypoint_follower-8]: process started with pid [20117]
[INFO] [lifecycle_manager-9]: process started with pid [20119]
[controller_server-4] [INFO] [1687897476.993618860] [controller_server]:
[controller_server-4] controller_server lifecycle node launched.
[controller_server-4] Waiting on external lifecycle transitions to activate
[controller_server-4] See https://design.ros2.org/articles/node_lifecycle.html for more information.
[controller_server-4] [INFO] [1687897477.004083369] [controller_server]: Creating controller server
[lifecycle_manager-3] [INFO] [1687897477.677967594] [lifecycle_manager_slam]: Creating
[lifecycle_manager-9] [INFO] [1687897477.690304225] [lifecycle_manager_navigation]: Creating
[sync_slam_toolbox_node-1] [INFO] [1687897477.700001144] [slam_toolbox]: Node using stack size 160000000
[recoveries_server-6] [INFO] [1687897477.761758608] [recoveries_server]:
[recoveries_server-6] recoveries_server lifecycle node launched.
[recoveries_server-6] Waiting on external lifecycle transitions to activate
[recoveries_server-6] See https://design.ros2.org/articles/node_lifecycle.html for more information.
[waypoint_follower-8] [INFO] [1687897477.832771850] [waypoint_follower]:
[waypoint_follower-8] waypoint_follower lifecycle node launched.
[waypoint_follower-8] Waiting on external lifecycle transitions to activate
[waypoint_follower-8] See https://design.ros2.org/articles/node_lifecycle.html for more information.
[waypoint_follower-8] [INFO] [1687897477.833017206] [waypoint_follower]: Creating
[bt_navigator-7] [INFO] [1687897477.836603364] [bt_navigator]:
[bt_navigator-7] bt_navigator lifecycle node launched.
[bt_navigator-7] Waiting on external lifecycle transitions to activate
[bt_navigator-7] See https://design.ros2.org/articles/node_lifecycle.html for more information.
[bt_navigator-7] [INFO] [1687897477.836845456] [bt_navigator]: Creating
[lifecycle_manager-3] [INFO] [1687897477.841127648] [lifecycle_manager_slam]: Creating and initializing lifecycle service clients
[lifecycle_manager-3] [INFO] [1687897477.844074767] [lifecycle_manager_slam]: Starting managed nodes bringup...
[lifecycle_manager-3] [INFO] [1687897477.844156531] [lifecycle_manager_slam]: Configuring map_saver
[lifecycle_manager-9] [INFO] [1687897477.851579964] [lifecycle_manager_navigation]: Creating and initializing lifecycle service clients
[planner_server-5] [INFO] [1687897477.892389626] [planner_server]:
[planner_server-5] planner_server lifecycle node launched.
[planner_server-5] Waiting on external lifecycle transitions to activate
[planner_server-5] See https://design.ros2.org/articles/node_lifecycle.html for more information.
[planner_server-5] [INFO] [1687897477.907909868] [planner_server]: Creating
[controller_server-4] [INFO] [1687897477.922461679] [local_costmap.local_costmap]:
[controller_server-4] local_costmap lifecycle node launched.
[controller_server-4] Waiting on external lifecycle transitions to activate
[controller_server-4] See https://design.ros2.org/articles/node_lifecycle.html for more information.
[controller_server-4] [INFO] [1687897477.923622279] [local_costmap.local_costmap]: Creating Costmap
[map_saver_server-2] [INFO] [1687897477.930064832] [map_saver]:
[map_saver_server-2] map_saver lifecycle node launched.
[map_saver_server-2] Waiting on external lifecycle transitions to activate
[map_saver_server-2] See https://design.ros2.org/articles/node_lifecycle.html for more information.
[map_saver_server-2] [INFO] [1687897477.930345550] [map_saver]: Creating
[planner_server-5] [INFO] [1687897478.025467483] [global_costmap.global_costmap]:
[planner_server-5] global_costmap lifecycle node launched.
[planner_server-5] Waiting on external lifecycle transitions to activate
[planner_server-5] See https://design.ros2.org/articles/node_lifecycle.html for more information.
[planner_server-5] [INFO] [1687897478.026734201] [global_costmap.global_costmap]: Creating Costmap
[sync_slam_toolbox_node-1] [INFO] [1687897478.378075207] [slam_toolbox]: Using solver plugin solver_plugins::CeresSolver
[sync_slam_toolbox_node-1] [INFO] [1687897478.379665140] [slam_toolbox]: CeresSolver: Using SCHUR_JACOBI preconditioner.
[lifecycle_manager-9] [INFO] [1687897478.608352092] [lifecycle_manager_navigation]: Starting managed nodes bringup...
[lifecycle_manager-9] [INFO] [1687897478.608447680] [lifecycle_manager_navigation]: Configuring controller_server
[controller_server-4] [INFO] [1687897478.677462169] [controller_server]: Configuring controller interface
[controller_server-4] [INFO] [1687897478.678428392] [controller_server]: Controller frequency set to 2.0000Hz
[controller_server-4] [INFO] [1687897478.678564271] [local_costmap.local_costmap]: Configuring
[controller_server-4] [INFO] [1687897478.693929882] [local_costmap.local_costmap]: Using plugin "inflation_layer"
[controller_server-4] [INFO] [1687897478.707056311] [local_costmap.local_costmap]: Initialized plugin "inflation_layer"
[controller_server-4] [INFO] [1687897478.707143036] [local_costmap.local_costmap]: Using plugin "voxel_layer"
[controller_server-4] [INFO] [1687897478.713198594] [local_costmap.local_costmap]: Subscribed to Topics: pointcloud scan
[controller_server-4] [INFO] [1687897478.764834095] [local_costmap.local_costmap]: Initialized plugin "voxel_layer"
[controller_server-4] [INFO] [1687897478.812477593] [controller_server]: Created progress_checker : progress_checker of type nav2_controller::SimpleProgressChecker
[controller_server-4] [INFO] [1687897478.814975603] [controller_server]: Created goal_checker : goal_checker of type nav2_controller::SimpleGoalChecker
[controller_server-4] [INFO] [1687897478.822157936] [controller_server]: Created controller : FollowPath of type dwb_core::DWBLocalPlanner
[controller_server-4] [INFO] [1687897478.826926871] [controller_server]: Setting transform_tolerance to 1.000000
[controller_server-4] [INFO] [1687897478.899713000] [controller_server]: Using critic "RotateToGoal" (dwb_critics::RotateToGoalCritic)
[controller_server-4] [INFO] [1687897478.904047642] [controller_server]: Critic plugin initialized
[controller_server-4] [INFO] [1687897478.904303623] [controller_server]: Using critic "Oscillation" (dwb_critics::OscillationCritic)
[controller_server-4] [INFO] [1687897478.906432718] [controller_server]: Critic plugin initialized
[controller_server-4] [INFO] [1687897478.906671290] [controller_server]: Using critic "BaseObstacle" (dwb_critics::BaseObstacleCritic)
[controller_server-4] [INFO] [1687897478.906762430] [controller_server]: Critic plugin initialized
[controller_server-4] [INFO] [1687897478.906855843] [controller_server]: Using critic "GoalAlign" (dwb_critics::GoalAlignCritic)
[controller_server-4] [INFO] [1687897478.912265162] [controller_server]: Critic plugin initialized
[controller_server-4] [INFO] [1687897478.914041696] [controller_server]: Using critic "PathAlign" (dwb_critics::PathAlignCritic)
[controller_server-4] [INFO] [1687897478.916864201] [controller_server]: Critic plugin initialized
[controller_server-4] [INFO] [1687897478.917095060] [controller_server]: Using critic "PathDist" (dwb_critics::PathDistCritic)
[controller_server-4] [INFO] [1687897478.930058314] [controller_server]: Critic plugin initialized
[controller_server-4] [INFO] [1687897478.930266868] [controller_server]: Using critic "GoalDist" (dwb_critics::GoalDistCritic)
[controller_server-4] [INFO] [1687897478.930751564] [controller_server]: Critic plugin initialized
[controller_server-4] [INFO] [1687897478.930809807] [controller_server]: Controller Server has FollowPath controllers available.
[lifecycle_manager-9] [INFO] [1687897478.961384444] [lifecycle_manager_navigation]: Configuring planner_server
[planner_server-5] [INFO] [1687897478.962160162] [planner_server]: Configuring
[planner_server-5] [INFO] [1687897478.962244838] [global_costmap.global_costmap]: Configuring
[planner_server-5] [INFO] [1687897478.977922848] [global_costmap.global_costmap]: Using plugin "static_layer"
[planner_server-5] [INFO] [1687897478.987980841] [global_costmap.global_costmap]: Subscribing to the map topic (/map) with transient local durability
[planner_server-5] [INFO] [1687897478.992087056] [global_costmap.global_costmap]: Subscribing to updates
[planner_server-5] [INFO] [1687897478.995107075] [global_costmap.global_costmap]: Initialized plugin "static_layer"
[planner_server-5] [INFO] [1687897478.995187175] [global_costmap.global_costmap]: Using plugin "obstacle_layer"
[planner_server-5] [INFO] [1687897478.995486261] [global_costmap.global_costmap]: Subscribed to Topics: pointcloud scan
[planner_server-5] [INFO] [1687897479.023881561] [global_costmap.global_costmap]: Initialized plugin "obstacle_layer"
[planner_server-5] [INFO] [1687897479.023983006] [global_costmap.global_costmap]: Using plugin "inflation_layer"
[planner_server-5] [INFO] [1687897479.026776038] [global_costmap.global_costmap]: Initialized plugin "inflation_layer"
[planner_server-5] [INFO] [1687897479.069258134] [planner_server]: Created global planner plugin GridBased of type nav2_navfn_planner/NavfnPlanner
[planner_server-5] [INFO] [1687897479.069370523] [planner_server]: Configuring plugin GridBased of type NavfnPlanner
[planner_server-5] [INFO] [1687897479.098047469] [planner_server]: Planner Server has GridBased planners available.
[lifecycle_manager-9] [INFO] [1687897479.115285907] [lifecycle_manager_navigation]: Configuring recoveries_server
[recoveries_server-6] [INFO] [1687897479.116255010] [recoveries_server]: Configuring
[recoveries_server-6] [INFO] [1687897479.143467788] [recoveries_server]: Creating recovery plugin spin of type nav2_recoveries/Spin
[recoveries_server-6] [INFO] [1687897479.146749356] [recoveries_server]: Configuring spin
[recoveries_server-6] [INFO] [1687897479.184143205] [recoveries_server]: Creating recovery plugin back_up of type nav2_recoveries/BackUp
[recoveries_server-6] [INFO] [1687897479.187617357] [recoveries_server]: Configuring back_up
[recoveries_server-6] [INFO] [1687897479.219530300] [recoveries_server]: Creating recovery plugin wait of type nav2_recoveries/Wait
[recoveries_server-6] [INFO] [1687897479.223362198] [recoveries_server]: Configuring wait
[lifecycle_manager-9] [INFO] [1687897479.269015937] [lifecycle_manager_navigation]: Configuring bt_navigator
[bt_navigator-7] [INFO] [1687897479.269850186] [bt_navigator]: Configuring
[bt_navigator-7] [INFO] [1687897479.414917011] [bt_navigator_rclcpp_node]: Waiting for "compute_path_to_pose" action server
[bt_navigator-7] [INFO] [1687897479.415613461] [bt_navigator_rclcpp_node]: "ComputePathToPose" BtActionNode initialized
[bt_navigator-7] [INFO] [1687897479.420215412] [bt_navigator_rclcpp_node]: Waiting for "global_costmap/clear_entirely_global_costmap" service
[bt_navigator-7] [INFO] [1687897479.420472961] [bt_navigator_rclcpp_node]: "ClearGlobalCostmap-Context" BtServiceNode initialized
[bt_navigator-7] [INFO] [1687897479.440098555] [bt_navigator_rclcpp_node]: Waiting for "follow_path" action server
[bt_navigator-7] [INFO] [1687897479.440442155] [bt_navigator_rclcpp_node]: "FollowPath" BtActionNode initialized
[bt_navigator-7] [INFO] [1687897479.445258037] [bt_navigator_rclcpp_node]: Waiting for "local_costmap/clear_entirely_local_costmap" service
[bt_navigator-7] [INFO] [1687897479.445530339] [bt_navigator_rclcpp_node]: "ClearLocalCostmap-Context" BtServiceNode initialized
[bt_navigator-7] [INFO] [1687897479.447950872] [bt_navigator_rclcpp_node]: Waiting for "local_costmap/clear_entirely_local_costmap" service
[bt_navigator-7] [INFO] [1687897479.448600120] [bt_navigator_rclcpp_node]: "ClearLocalCostmap-Subtree" BtServiceNode initialized
[bt_navigator-7] [INFO] [1687897479.451468259] [bt_navigator_rclcpp_node]: Waiting for "global_costmap/clear_entirely_global_costmap" service
[bt_navigator-7] [INFO] [1687897479.451697550] [bt_navigator_rclcpp_node]: "ClearGlobalCostmap-Subtree" BtServiceNode initialized
[bt_navigator-7] [INFO] [1687897479.465294115] [bt_navigator_rclcpp_node]: Waiting for "spin" action server
[bt_navigator-7] [INFO] [1687897479.465597650] [bt_navigator_rclcpp_node]: "Spin" BtActionNode initialized
[bt_navigator-7] [INFO] [1687897479.481273067] [bt_navigator_rclcpp_node]: Waiting for "wait" action server
[bt_navigator-7] [INFO] [1687897479.481649726] [bt_navigator_rclcpp_node]: "Wait" BtActionNode initialized
[lifecycle_manager-9] [INFO] [1687897479.487414550] [lifecycle_manager_navigation]: Configuring waypoint_follower
[waypoint_follower-8] [INFO] [1687897479.488267327] [waypoint_follower]: Configuring
[lifecycle_manager-9] [INFO] [1687897479.576507615] [lifecycle_manager_navigation]: Activating controller_server
[controller_server-4] [INFO] [1687897479.577308710] [controller_server]: Activating
[controller_server-4] [INFO] [1687897479.577390474] [local_costmap.local_costmap]: Activating
[controller_server-4] [INFO] [1687897479.577419532] [local_costmap.local_costmap]: Checking transform
[controller_server-4] [INFO] [1687897479.577734011] [local_costmap.local_costmap]: start
[lifecycle_manager-9] [INFO] [1687897479.589910891] [lifecycle_manager_navigation]: Activating planner_server
[planner_server-5] [INFO] [1687897479.590690960] [planner_server]: Activating
[planner_server-5] [INFO] [1687897479.590771444] [global_costmap.global_costmap]: Activating
[planner_server-5] [INFO] [1687897479.590837592] [global_costmap.global_costmap]: Checking transform
[planner_server-5] [INFO] [1687897479.590912667] [global_costmap.global_costmap]: Timed out waiting for transform from base_footprint to map to become available, tf error: Invalid frame ID "base_footprint" passed to canTransform argument source_frame - frame does not exist
[planner_server-5] [INFO] [1687897480.090938438] [global_costmap.global_costmap]: Timed out waiting for transform from base_footprint to map to become available, tf error: Invalid frame ID "base_footprint" passed to canTransform argument source_frame - frame does not exist
[planner_server-5] [INFO] [1687897480.590931762] [global_costmap.global_costmap]: Timed out waiting for transform from base_footprint to map to become available, tf error: Invalid frame ID "base_footprint" passed to canTransform argument source_frame - frame does not exist
[planner_server-5] [INFO] [1687897481.090985762] [global_costmap.global_costmap]: Timed out waiting for transform from base_footprint to map to become available, tf error: Invalid frame ID "base_footprint" passed to canTransform argument source_frame - frame does not exist
[planner_server-5] [INFO] [1687897481.590977554] [global_costmap.global_costmap]: Timed out waiting for transform from base_footprint to map to become available, tf error: Invalid frame ID "base_footprint" passed to canTransform argument source_frame - frame does not exist
[planner_server-5] [INFO] [1687897482.090981859] [global_costmap.global_costmap]: Timed out waiting for transform from base_footprint to map to become available, tf error: Invalid frame ID "base_footprint" passed to canTransform argument source_frame - frame does not exist
[planner_server-5] [INFO] [1687897482.590986743] [global_costmap.global_costmap]: Timed out waiting for transform from base_footprint to map to become available, tf error: Invalid frame ID "base_footprint" passed to canTransform argument source_frame - frame does not exist
[planner_server-5] [INFO] [1687897483.090980459] [global_costmap.global_costmap]: Timed out waiting for transform from base_footprint to map to become available, tf error: Invalid frame ID "base_footprint" passed to canTransform argument source_frame - frame does not exist
Meanwhile, I can see the transform, infact, being published:
prompt$ ros2 topic echo /tf
transforms:
- header:
stamp:
sec: 1687897501
nanosec: 185383201
frame_id: map
child_frame_id: odom
transform:
translation:
x: 0.0
y: 0.0
z: 0.0
rotation:
x: 0.0
y: 0.0
z: 0.0
w: 1.0
---
transforms:
- header:
stamp:
sec: 1687897500
nanosec: 191622225
frame_id: odom
child_frame_id: base_footprint
transform:
translation:
x: 0.008160634569804677
y: -0.01861611644861179
z: 0.0
rotation:
x: -0.0
y: 0.0
z: 0.048092251664442254
w: -0.9988428982226604
---
Any ideas here?
Problem type 5: nav2 drops the "scan_link" for unknown reason forever!
prompt$ ros2 launch robot_user_robot_nav nav2_bringup_tb3_revised_launch.py slam:=True
[INFO] [launch]: All log files can be found below /home/robot_user/.ros/log/2023-06-27-15-28-48-813140-robot_user-Xavier-20699
[INFO] [launch]: Default logging verbosity is set to INFO
[INFO] [sync_slam_toolbox_node-1]: process started with pid [20701]
[INFO] [map_saver_server-2]: process started with pid [20703]
[INFO] [lifecycle_manager-3]: process started with pid [20705]
[INFO] [controller_server-4]: process started with pid [20707]
[INFO] [planner_server-5]: process started with pid [20709]
[INFO] [recoveries_server-6]: process started with pid [20711]
[INFO] [bt_navigator-7]: process started with pid [20715]
[INFO] [waypoint_follower-8]: process started with pid [20732]
[INFO] [lifecycle_manager-9]: process started with pid [20744]
[lifecycle_manager-3] [INFO] [1687897730.147999187] [lifecycle_manager_slam]: Creating
[lifecycle_manager-3] [INFO] [1687897730.156947923] [lifecycle_manager_slam]: Creating and initializing lifecycle service clients
[lifecycle_manager-3] [INFO] [1687897730.158329208] [lifecycle_manager_slam]: Starting managed nodes bringup...
[lifecycle_manager-3] [INFO] [1687897730.158433981] [lifecycle_manager_slam]: Configuring map_saver
[map_saver_server-2] [INFO] [1687897730.319350669] [map_saver]:
[map_saver_server-2] map_saver lifecycle node launched.
[map_saver_server-2] Waiting on external lifecycle transitions to activate
[map_saver_server-2] See https://design.ros2.org/articles/node_lifecycle.html for more information.
[map_saver_server-2] [INFO] [1687897730.319593657] [map_saver]: Creating
[controller_server-4] [INFO] [1687897730.467533793] [controller_server]:
[controller_server-4] controller_server lifecycle node launched.
[controller_server-4] Waiting on external lifecycle transitions to activate
[controller_server-4] See https://design.ros2.org/articles/node_lifecycle.html for more information.
[waypoint_follower-8] [INFO] [1687897730.485658987] [waypoint_follower]:
[waypoint_follower-8] waypoint_follower lifecycle node launched.
[waypoint_follower-8] Waiting on external lifecycle transitions to activate
[waypoint_follower-8] See https://design.ros2.org/articles/node_lifecycle.html for more information.
[waypoint_follower-8] [INFO] [1687897730.485906967] [waypoint_follower]: Creating
[controller_server-4] [INFO] [1687897730.486336173] [controller_server]: Creating controller server
[lifecycle_manager-9] [INFO] [1687897730.584219181] [lifecycle_manager_navigation]: Creating
[sync_slam_toolbox_node-1] [INFO] [1687897730.615047570] [slam_toolbox]: Node using stack size 160000000
[planner_server-5] [INFO] [1687897730.637450931] [planner_server]:
[planner_server-5] planner_server lifecycle node launched.
[planner_server-5] Waiting on external lifecycle transitions to activate
[planner_server-5] See https://design.ros2.org/articles/node_lifecycle.html for more information.
[bt_navigator-7] [INFO] [1687897730.660435857] [bt_navigator]:
[bt_navigator-7] bt_navigator lifecycle node launched.
[bt_navigator-7] Waiting on external lifecycle transitions to activate
[bt_navigator-7] See https://design.ros2.org/articles/node_lifecycle.html for more information.
[bt_navigator-7] [INFO] [1687897730.663227356] [bt_navigator]: Creating
[planner_server-5] [INFO] [1687897730.680982228] [planner_server]: Creating
[map_saver_server-2] [INFO] [1687897730.724289770] [map_saver]: Configuring
[lifecycle_manager-3] [INFO] [1687897730.737060041] [lifecycle_manager_slam]: Activating map_saver
[map_saver_server-2] [INFO] [1687897730.738055419] [map_saver]: Activating
[lifecycle_manager-3] [INFO] [1687897730.741696913] [lifecycle_manager_slam]: Managed nodes are active
[lifecycle_manager-9] [INFO] [1687897730.782701332] [lifecycle_manager_navigation]: Creating and initializing lifecycle service clients
[controller_server-4] [INFO] [1687897730.809114653] [local_costmap.local_costmap]:
[controller_server-4] local_costmap lifecycle node launched.
[controller_server-4] Waiting on external lifecycle transitions to activate
[controller_server-4] See https://design.ros2.org/articles/node_lifecycle.html for more information.
[controller_server-4] [INFO] [1687897730.822651298] [local_costmap.local_costmap]: Creating Costmap
[recoveries_server-6] [INFO] [1687897730.827696254] [recoveries_server]:
[recoveries_server-6] recoveries_server lifecycle node launched.
[recoveries_server-6] Waiting on external lifecycle transitions to activate
[recoveries_server-6] See https://design.ros2.org/articles/node_lifecycle.html for more information.
[planner_server-5] [INFO] [1687897730.915495813] [global_costmap.global_costmap]:
[planner_server-5] global_costmap lifecycle node launched.
[planner_server-5] Waiting on external lifecycle transitions to activate
[planner_server-5] See https://design.ros2.org/articles/node_lifecycle.html for more information.
[planner_server-5] [INFO] [1687897730.916678881] [global_costmap.global_costmap]: Creating Costmap
[lifecycle_manager-9] [INFO] [1687897730.956777814] [lifecycle_manager_navigation]: Starting managed nodes bringup...
[lifecycle_manager-9] [INFO] [1687897730.957099014] [lifecycle_manager_navigation]: Configuring controller_server
[sync_slam_toolbox_node-1] [INFO] [1687897731.128550246] [slam_toolbox]: Using solver plugin solver_plugins::CeresSolver
[sync_slam_toolbox_node-1] [INFO] [1687897731.133108810] [slam_toolbox]: CeresSolver: Using SCHUR_JACOBI preconditioner.
[sync_slam_toolbox_node-1] [INFO] [1687897733.991871753] [slam_toolbox]: Message Filter dropping message: frame 'scan_link' at time 1687897733.838 for reason 'Unknown'
[sync_slam_toolbox_node-1] [INFO] [1687897734.065717623] [slam_toolbox]: Message Filter dropping message: frame 'scan_link' at time 1687897733.912 for reason 'Unknown'
[sync_slam_toolbox_node-1] [INFO] [1687897734.145279140] [slam_toolbox]: Message Filter dropping message: frame 'scan_link' at time 1687897733.992 for reason 'Unknown'
[sync_slam_toolbox_node-1] [INFO] [1687897734.219810773] [slam_toolbox]: Message Filter dropping message: frame 'scan_link' at time 1687897734.065 for reason 'Unknown'
[sync_slam_toolbox_node-1] [INFO] [1687897734.298818502] [slam_toolbox]: Message Filter dropping message: frame 'scan_link' at time 1687897734.145 for reason 'Unknown'
[sync_slam_toolbox_node-1] [INFO] [1687897734.378642464] [slam_toolbox]: Message Filter dropping message: frame 'scan_link' at time 1687897734.219 for reason 'Unknown'
[sync_slam_toolbox_node-1] [INFO] [1687897734.452426379] [slam_toolbox]: Message Filter dropping message: frame 'scan_link' at time 1687897734.299 for reason 'Unknown'
Meanwhile, I can see the /scan topic publishing correctly!
prompt$ ros2 topic echo /scan
header:
stamp:
sec: 1687897800
nanosec: 929012736
frame_id: scan_link
angle_min: -3.1241390705108643
angle_max: 3.1415927410125732
angle_increment: 0.0034828970674425364
time_increment: 4.4161810365039855e-05
scan_time: 0.07944709807634354
range_min: 0.15000000596046448
range_max: 25.0
ranges:
- 17.90399932861328
- 17.90399932861328
- 17.90399932861328
- 17.90399932861328
- 17.95199966430664
- 17.95199966430664
- 17.95199966430664
- 17.95199966430664
- '...'
intensities:
- 47.0
- 47.0
- 47.0
- 47.0
- 47.0
- 47.0
- '...'
---
What could cause this one?
Here is my nav2 launch file:
import os
from ament_index_python.packages import get_package_share_directory
from launch import LaunchDescription
from launch.actions import DeclareLaunchArgument, ExecuteProcess, IncludeLaunchDescription
from launch.conditions import IfCondition
from launch.launch_description_sources import PythonLaunchDescriptionSource
from launch.substitutions import LaunchConfiguration, PythonExpression
from launch_ros.actions import Node
from ament_index_python.packages import get_package_share_directory
def generate_launch_description():
# Get the launch directory
bringup_dir = get_package_share_directory('nav2_bringup')
launch_dir = os.path.join(bringup_dir, 'launch')
pkg_share = FindPackageShare(package='user_robot_nav').find('user_robot_nav')
# Create the launch configuration variables
slam = LaunchConfiguration('slam')
namespace = LaunchConfiguration('namespace')
use_namespace = LaunchConfiguration('use_namespace')
map_yaml_file = LaunchConfiguration('map')
use_sim_time = LaunchConfiguration('use_sim_time')
params_file = LaunchConfiguration('params_file')
default_bt_xml_filename = LaunchConfiguration('default_bt_xml_filename')
autostart = LaunchConfiguration('autostart')
# Launch configuration variables specific to simulation
rviz_config_file = LaunchConfiguration('rviz_config_file')
use_rviz = LaunchConfiguration('use_rviz')
# Map fully qualified names to relative ones so the node's namespace can be prepended.
# In case of the transforms (tf), currently, there doesn't seem to be a better alternative
# https://github.com/ros/geometry2/issues/32
# https://github.com/ros/robot_state_publisher/pull/30
# TODO(orduno) Substitute with `PushNodeRemapping`
# https://github.com/ros2/launch_ros/issues/56
remappings = [('/tf', 'tf'),
('/tf_static', 'tf_static')]
# Declare the launch arguments
declare_namespace_cmd = DeclareLaunchArgument(
'namespace',
default_value='',
description='Top-level namespace')
declare_use_namespace_cmd = DeclareLaunchArgument(
'use_namespace',
default_value='false',
description='Whether to apply a namespace to the navigation stack')
declare_slam_cmd = DeclareLaunchArgument(
'slam',
default_value='False',
description='Whether run a SLAM')
declare_map_yaml_cmd = DeclareLaunchArgument(
'map',
default_value=os.path.join(pkg_share, 'maps', 'user_robot_map.yaml'),
description='Full path to map file to load')
declare_use_sim_time_cmd = DeclareLaunchArgument(
'use_sim_time',
default_value='true',
description='Use simulation (Gazebo) clock if true')
declare_params_file_cmd = DeclareLaunchArgument(
'params_file',
default_value=os.path.join(pkg_share, 'params', 'user_robot_nav2_params.yaml'),
description='Full path to the ROS2 parameters file to use for all launched nodes')
declare_bt_xml_cmd = DeclareLaunchArgument(
'default_bt_xml_filename',
default_value=os.path.join(
get_package_share_directory('nav2_bt_navigator'),
'behavior_trees', 'navigate_w_replanning_and_recovery.xml'),
description='Full path to the behavior tree xml file to use')
declare_autostart_cmd = DeclareLaunchArgument(
'autostart', default_value='true',
description='Automatically startup the nav2 stack')
declare_rviz_config_file_cmd = DeclareLaunchArgument(
'rviz_config_file',
default_value=os.path.join(bringup_dir, 'rviz', 'nav2_default_view.rviz'),
description='Full path to the RVIZ config file to use')
declare_use_simulator_cmd = DeclareLaunchArgument(
'use_simulator',
default_value='True',
description='Whether to start the simulator')
declare_use_robot_state_pub_cmd = DeclareLaunchArgument(
'use_robot_state_pub',
default_value='True',
description='Whether to start the robot state publisher')
declare_use_rviz_cmd = DeclareLaunchArgument(
'use_rviz',
default_value='True',
description='Whether to start RVIZ')
# Specify the actions
rviz_cmd = IncludeLaunchDescription(
PythonLaunchDescriptionSource(os.path.join(launch_dir, 'rviz_launch.py')),
condition=IfCondition(use_rviz),
launch_arguments={'namespace': '',
'use_namespace': 'False',
'rviz_config': rviz_config_file}.items())
bringup_cmd = IncludeLaunchDescription(
PythonLaunchDescriptionSource(os.path.join(launch_dir, 'bringup_launch.py')),
launch_arguments={'namespace': namespace,
'use_namespace': use_namespace,
'slam': slam,
'map': map_yaml_file,
'use_sim_time': use_sim_time,
'params_file': params_file,
'default_bt_xml_filename': default_bt_xml_filename,
'autostart': autostart}.items())
# Create the launch description and populate
ld = LaunchDescription()
# Declare the launch options
ld.add_action(declare_namespace_cmd)
ld.add_action(declare_use_namespace_cmd)
ld.add_action(declare_slam_cmd)
ld.add_action(declare_map_yaml_cmd)
ld.add_action(declare_use_sim_time_cmd)
ld.add_action(declare_params_file_cmd)
ld.add_action(declare_bt_xml_cmd)
ld.add_action(declare_autostart_cmd)
ld.add_action(declare_rviz_config_file_cmd)
ld.add_action(declare_use_rviz_cmd)
# Add the actions to launch all of the navigation nodes
ld.add_action(rviz_cmd)
ld.add_action(bringup_cmd)
return ld
Here is my nav2 YAML settings file:
amcl:
ros__parameters:
use_sim_time: False
alpha1: 0.002
alpha2: 0.002
alpha3: 0.002
alpha4: 0.002
alpha5: 0.002
base_frame_id: "base_footprint"
beam_skip_distance: 0.5
beam_skip_error_threshold: 0.9
beam_skip_threshold: 0.3
do_beamskip: false
global_frame_id: "map"
initial_pose: [0.0, 0.0, 0.0, 0.0]
lambda_short: 0.1
laser_likelihood_max_dist: 2.0
laser_max_range: 100.0
laser_min_range: -1.0
laser_model_type: "likelihood_field"
max_beams: 60
max_particles: 2000
min_particles: 500
odom_frame_id: "odom"
pf_err: 0.05
pf_z: 0.99
recovery_alpha_fast: 0.0
recovery_alpha_slow: 0.0
resample_interval: 1
robot_model_type: "differential"
save_pose_rate: 0.5
set_initial_pose: True
sigma_hit: 0.2
tf_broadcast: true
transform_tolerance: 1.0
update_min_a: 0.2
update_min_d: 0.25
z_hit: 0.5
z_max: 0.05
z_rand: 0.5
z_short: 0.05
scan_topic: scan
amcl_map_client:
ros__parameters:
use_sim_time: False
amcl_rclcpp_node:
ros__parameters:
use_sim_time: False
bt_navigator:
ros__parameters:
use_sim_time: False
global_frame: map
robot_base_frame: base_link
odom_topic: /odom #/odometry/filtered
enable_groot_monitoring: True
groot_zmq_publisher_port: 1666
groot_zmq_server_port: 1667
default_bt_xml_filename: "navigate_w_replanning_and_recovery.xml"
plugin_lib_names:
- nav2_compute_path_to_pose_action_bt_node
- nav2_follow_path_action_bt_node
- nav2_back_up_action_bt_node
- nav2_spin_action_bt_node
- nav2_wait_action_bt_node
- nav2_clear_costmap_service_bt_node
- nav2_is_stuck_condition_bt_node
- nav2_goal_reached_condition_bt_node
- nav2_goal_updated_condition_bt_node
- nav2_initial_pose_received_condition_bt_node
- nav2_reinitialize_global_localization_service_bt_node
- nav2_rate_controller_bt_node
- nav2_distance_controller_bt_node
- nav2_speed_controller_bt_node
- nav2_truncate_path_action_bt_node
- nav2_goal_updater_node_bt_node
- nav2_recovery_node_bt_node
- nav2_pipeline_sequence_bt_node
- nav2_round_robin_node_bt_node
- nav2_transform_available_condition_bt_node
- nav2_time_expired_condition_bt_node
- nav2_distance_traveled_condition_bt_node
bt_navigator_rclcpp_node:
ros__parameters:
use_sim_time: False
controller_server:
ros__parameters:
use_sim_time: False
controller_frequency: 2.0
min_x_velocity_threshold: 0.001
min_y_velocity_threshold: 0.5
min_theta_velocity_threshold: 0.001
progress_checker_plugin: "progress_checker"
goal_checker_plugin: "goal_checker"
controller_plugins: ["FollowPath"]
# Progress checker parameters
progress_checker:
plugin: "nav2_controller::SimpleProgressChecker"
required_movement_radius: 0.5
movement_time_allowance: 10.0
# Goal checker parameters
goal_checker:
plugin: "nav2_controller::SimpleGoalChecker"
xy_goal_tolerance: 0.25
yaw_goal_tolerance: 0.25
stateful: True
# DWB parameters
FollowPath:
plugin: "dwb_core::DWBLocalPlanner"
debug_trajectory_details: True
min_vel_x: 0.0
min_vel_y: 0.0
# Default 0.26 for max_vel_x and max_speed_xy and 1.0 for max_vel_theta
max_vel_x: 0.26
max_vel_y: 0.0
max_vel_theta: 1.0
min_speed_xy: 0.0
max_speed_xy: 0.26
min_speed_theta: 0.0
# Add high threshold velocity for turtlebot 3 issue.
# https://github.com/ROBOTIS-GIT/turtlebot3_simulations/issues/75
acc_lim_x: 2.5
acc_lim_y: 0.0
acc_lim_theta: 3.2
decel_lim_x: -2.5
decel_lim_y: 0.0
decel_lim_theta: -3.2
vx_samples: 20
vy_samples: 5
vtheta_samples: 20
sim_time: 1.7
linear_granularity: 0.05
angular_granularity: 0.025
transform_tolerance: 0.2
xy_goal_tolerance: 0.25
trans_stopped_velocity: 0.25
short_circuit_trajectory_evaluation: True
stateful: True
critics: ["RotateToGoal", "Oscillation", "BaseObstacle", "GoalAlign", "PathAlign", "PathDist", "GoalDist"]
BaseObstacle.scale: 0.02
PathAlign.scale: 32.0
PathAlign.forward_point_distance: 0.1
GoalAlign.scale: 24.0
GoalAlign.forward_point_distance: 0.1
PathDist.scale: 32.0
GoalDist.scale: 24.0
RotateToGoal.scale: 32.0
RotateToGoal.slowing_factor: 5.0
RotateToGoal.lookahead_time: -1.0
controller_server_rclcpp_node:
ros__parameters:
use_sim_time: False
local_costmap:
local_costmap:
ros__parameters:
update_frequency: 5.0
publish_frequency: 2.0
global_frame: odom
robot_base_frame: base_footprint
use_sim_time: False
rolling_window: True
width: 6
height: 6
resolution: 0.05
robot_radius: 0.6
plugins: ["inflation_layer", "voxel_layer"]
voxel_layer:
plugin: "nav2_costmap_2d::VoxelLayer"
enabled: True
footprint_clearing_enabled: False
publish_voxel_map: True
origin_z: 0.0
z_resolution: 0.125
z_voxels: 16
max_obstacle_height: 2.0
unknown_threshold: 15
mark_threshold: 0
observation_sources: pointcloud
combination_method: 1
pointcloud: # no frame set, uses frame from message
topic: /stereo/points #/cloud_in
max_obstacle_height: 2.0
min_obstacle_height: 0.6 # was 0.4
obstacle_range: 9.5
raytrace_range: 10.0
clearing: True #False
marking: True
data_type: "PointCloud2"
inflation_layer:
plugin: "nav2_costmap_2d::InflationLayer"
cost_scaling_factor: 3.0
inflation_radius: 0.55
always_send_full_costmap: True
local_costmap_client:
ros__parameters:
use_sim_time: False
local_costmap_rclcpp_node:
ros__parameters:
use_sim_time: False
global_costmap:
global_costmap:
ros__parameters:
update_frequency: 1.0
publish_frequency: 1.0
global_frame: map
robot_base_frame: base_footprint
use_sim_time: False
robot_radius: 0.6
resolution: 0.05
track_unknown_space: True
plugins: ["static_layer", "obstacle_layer", "inflation_layer"]
obstacle_layer:
plugin: "nav2_costmap_2d::ObstacleLayer"
enabled: True
observation_sources: pointcloud scan
combination_method: 1
pointcloud: # no frame set, uses frame from message
topic: /stereo/points #/cloud_in
max_obstacle_height: 2.0
min_obstacle_height: 0.6 # was 0.4
obstacle_range: 9.5
raytrace_range: 10.0
clearing: True #False
marking: True
data_type: "PointCloud2"
scan:
topic: /scan
max_obstacle_height: 2.0
min_obstacle_height: 0.6 # was 0.4
clearing: True #False
marking: True
data_type: "LaserScan"
static_layer:
plugin: "nav2_costmap_2d::StaticLayer"
enabled: True
map_subscribe_transient_local: True
subscribe_to_updates: True
inflation_layer:
plugin: "nav2_costmap_2d::InflationLayer"
cost_scaling_factor: 3.0
inflation_radius: 0.55
always_send_full_costmap: True
global_costmap_client:
ros__parameters:
use_sim_time: False
global_costmap_rclcpp_node:
ros__parameters:
use_sim_time: False
map_server:
ros__parameters:
use_sim_time: False
yaml_filename: "cafe.yaml"
map_saver:
ros__parameters:
use_sim_time: False
save_map_timeout: 5000
free_thresh_default: 0.25
occupied_thresh_default: 0.65
map_subscribe_transient_local: False
save_map_timeout: 5000
planner_server:
ros__parameters:
expected_planner_frequency: 2.0
use_sim_time: False
planner_plugins: ["GridBased"]
GridBased:
plugin: "nav2_navfn_planner/NavfnPlanner"
tolerance: 0.5
use_astar: false
allow_unknown: true
planner_server_rclcpp_node:
ros__parameters:
use_sim_time: False
recoveries_server:
ros__parameters:
costmap_topic: local_costmap/costmap_raw
footprint_topic: local_costmap/published_footprint
cycle_frequency: 10.0
recovery_plugins: ["spin", "back_up", "wait"]
spin:
plugin: "nav2_recoveries/Spin"
back_up:
plugin: "nav2_recoveries/BackUp"
wait:
plugin: "nav2_recoveries/Wait"
global_frame: odom
robot_base_frame: base_link
transform_timeout: 0.1
use_sim_time: False
simulate_ahead_time: 2.0
max_rotational_vel: 1.0
min_rotational_vel: 0.4
rotational_acc_lim: 3.2
robot_state_publisher:
ros__parameters:
use_sim_time: False
slam_toolbox:
ros__parameters:
# Plugin params
solver_plugin: solver_plugins::CeresSolver
ceres_linear_solver: SPARSE_NORMAL_CHOLESKY
ceres_preconditioner: SCHUR_JACOBI
ceres_trust_strategy: LEVENBERG_MARQUARDT
ceres_dogleg_type: TRADITIONAL_DOGLEG
ceres_loss_function: None
# ROS Parameters
odom_frame: odom
map_frame: map
base_frame: base_footprint
scan_topic: /scan
mode: mapping #localization
# if you'd like to immediately start continuing a map at a given pose
# or at the dock, but they are mutually exclusive, if pose is given
# will use pose
#map_file_name: test_steve
#map_start_pose: [0.0, 0.0, 0.0]
#map_start_at_dock: true
debug_logging: false
throttle_scans: 1
transform_publish_period: 0.02 #if 0 never publishes odometry
map_update_interval: 5.0
resolution: 0.05
max_laser_range: 20.0 #for rastering images
minimum_time_interval: 0.5
transform_timeout: 0.2
tf_buffer_duration: 30.
stack_size_to_use: 40000000 #// program needs a larger stack size to serialize large maps
enable_interactive_mode: true
# General Parameters
use_scan_matching: true
use_scan_barycenter: true
minimum_travel_distance: 0.5
minimum_travel_heading: 0.5
scan_buffer_size: 10
scan_buffer_maximum_scan_distance: 10.0
link_match_minimum_response_fine: 0.1
link_scan_maximum_distance: 1.5
loop_search_maximum_distance: 3.0
do_loop_closing: true
loop_match_minimum_chain_size: 10
loop_match_maximum_variance_coarse: 3.0
loop_match_minimum_response_coarse: 0.35
loop_match_minimum_response_fine: 0.45
# Correlation Parameters - Correlation Parameters
correlation_search_space_dimension: 0.5
correlation_search_space_resolution: 0.01
correlation_search_space_smear_deviation: 0.1
# Correlation Parameters - Loop Closure Parameters
loop_search_space_dimension: 8.0
loop_search_space_resolution: 0.05
loop_search_space_smear_deviation: 0.03
# Scan Matcher Parameters
distance_variance_penalty: 0.5
angle_variance_penalty: 1.0
fine_search_angle_offset: 0.00349
coarse_search_angle_offset: 0.349
coarse_angle_resolution: 0.0349
minimum_angle_penalty: 0.9
minimum_distance_penalty: 0.5
use_response_expansion: true
waypoint_follower:
ros__parameters:
loop_rate: 1
stop_on_failure: false
Sorry for the long post! As you can see, there are lots of weird problems.
Thanks for your help in advance.
Asked by Farbod on 2023-06-27 16:56:27 UTC
Answers
All the problems seem to have one thing in common: tf
. For disclosure I use ROS extensively but not ROS 2. I base my opinion based on what I've seen on ROS.
slam_toolbox cannot register the Lidar. It is unclear if the
tf
tree is complete, in particular, at the launch ofslam_toolbox
. Try runningros2 run tf2_ros tf2_echo odom scan_link
orros2 run tqt_tf_tree rqt_tf_tree
to view the entiretf
tree and see if there are any breaks (requires install).Sometimes, problem 1 does not occur, but "Robot is out of bounds of the costmap!" This is quite straight forward. It just says that the robot is currently not in a free region in the costmap, in particular the
obstacle_layer
for/scan
, and hence is unable to use raytracing to clear or mark obstacles. Moving the initial pose to an free area should fix this.nav2 can't get past controller server! Not sure, maybe controller waiting for initial
tf
as well?nav2 just sits there timing out waiting for transforms forever! Seems like the
tf
are being published at rates of 1Hz or more. If you want to use them at this rate be sure to increase the transform tolerances (timeout) in the respective nodes... if they are supposed to publish at higher update rates do check what could be throttling them.rqt_tf_tree
might help with idenfying slow updatingtf
.nav2 drops the "scan_link" for unknown reason forever! Similar to 1. Should find out if there is any break in the
tf
tree, or maybe slow update rates like in 4. that is causing the timeouts to be reported.
Asked by Guess Giant on 2023-06-28 02:27:37 UTC
Comments
Hello,
Thanks so much for the quick reply! I will try those for sure, and I think they will help.
Thanks again.
Asked by Farbod on 2023-06-28 08:44:35 UTC
I was going to comment on your reply with the results of my test, but the text box was not large enough. Could you please see my reply that I posted as an answer to my own question? Thanks a lot.
Asked by Farbod on 2023-06-28 11:43:28 UTC
Hi.
First, I have to say that the nav2 slam works fine on the first run (95% of times), when the robot is just booted. When I stop the nav2 after brining it up using the launch file using ctrl-C and run it again (after waiting some time until nodes disappear from the list "ros2 node list", I encounter these random problems that I described above.
Here is the result of echoing the transforms:
$ ros2 run tf2_ros tf2_echo odom scan_link
[INFO] [1687963541.009601577] [tf2_echo]: Waiting for transform odom -> scan_link: Invalid frame ID "odom" passed to canTransform argument target_frame - frame does not exist
At time 1687963541.596396082
- Translation: [-0.020, 0.000, 1.239]
- Rotation: in Quaternion [0.004, 0.000, 1.000, -0.005]
At time 1687963542.595545666
- Translation: [-0.020, 0.000, 1.239]
- Rotation: in Quaternion [0.004, 0.000, 1.000, -0.005]
At time 1687963543.597899375
- Translation: [-0.020, 0.000, 1.239]
- Rotation: in Quaternion [0.004, 0.000, 1.000, -0.005]
Another transform:
$ ros2 run tf2_ros tf2_echo odom base_footprint 2.0
[INFO] [1687968194.440594135] [tf2_echo]: Waiting for transform odom -> base_footprint: Invalid frame ID "odom" passed to canTransform argument target_frame - fram
e does not exist
At time 1687968194.881034063
- Translation: [-0.023, 0.000, 0.000]
- Rotation: in Quaternion [0.000, 0.000, 0.000, 1.000]
At time 1687968195.385934743
- Translation: [-0.023, 0.000, 0.000]
- Rotation: in Quaternion [0.000, 0.000, 0.000, 1.000]
At time 1687968195.881188582
- Translation: [-0.023, 0.000, 0.000]
- Rotation: in Quaternion [0.000, 0.000, 0.000, 1.000]
At time 1687968196.380709922
- Translation: [-0.023, 0.000, 0.000]
- Rotation: in Quaternion [0.000, 0.000, 0.000, 1.000]
Note that the above command publishes at the rate of 1 by default. Here is the actual rate with which the tf is published:
$ ros2 topic hz /tf
average rate: 56.453
min: 0.003s max: 0.029s std dev: 0.00917s window: 58
average rate: 56.138
min: 0.001s max: 0.029s std dev: 0.00901s window: 114
average rate: 56.053
min: 0.001s max: 0.029s std dev: 0.00904s window: 171
average rate: 55.940
min: 0.001s max: 0.029s std dev: 0.00903s window: 228
average rate: 55.870
min: 0.001s max: 0.029s std dev: 0.00904s window: 285
average rate: 55.826
min: 0.001s max: 0.029s std dev: 0.00902s window: 342
average rate: 55.825
min: 0.001s max: 0.031s std dev: 0.00907s window: 398
And the scan:
$ ros2 topic hz /scan
average rate: 12.826
min: 0.072s max: 0.081s std dev: 0.00351s window: 14
average rate: 12.830
min: 0.072s max: 0.081s std dev: 0.00337s window: 27
average rate: 12.833
min: 0.072s max: 0.082s std dev: 0.00324s window: 40
average rate: 12.849
min: 0.072s max: 0.082s std dev: 0.00318s window: 53
average rate: 12.844
min: 0.072s max: 0.082s std dev: 0.00304s window: 66
Also, as can be seen in my nav2 config file, all "transform_tolerance:" values are set to 1.0. I think that is the time duration of 1.0 second, which is way larger than the publishing period of the transforms. {Am I right here?]
transform_tolerance: 1.0
I would like to mention that the tf tree graph from rqt_tf_tree shows all frames are connected.
Anything else I can try? If all fails, I will have to restart the robot's computer every time I am testing nav2 for fine tuning.
Thanks so much!
Asked by Farbod on 2023-06-28 11:41:44 UTC
Comments
At least now we know that there is no broken/orphaned frames in the tf
tree. But what I don't know is if the tf
is published at 0.9Hz (which 1.0s tolerance is not enough), or 1.1Hz. What is the lowest update rate shown in rqt_tf_tree
? Next, we also should check the timestamp of the tf
. This can also be seen from rqt_tf_tree
or via rqt_monitor
: what is the most recent transform (in rqt_tf_tree
) or average delay (in tf_monitor
) like, especially at the point where the random problems appear?
Asked by Guess Giant on 2023-06-29 09:53:45 UTC
I tried to upload the PNG file of the transform tree, but apparently I don't have enough credit. :-) Here is what I see in the transform tree next to the branch connecting "odom" to "base_footprint":
Broadcaster: defualt_authority Average rate: 43.061 Buffer length: 0.325 Most recent transform: 1688051850.856241 Oldest transform: 1688051850.53112
The branch from "base_footprint" to "the base_link" shows:
Broadcaster: defualt_authority Average rate: 10000.0 Buffer length: 0.0 Most recent transform: 0.0 Oldest transform: 0.0
All branches that go from "base_link" to "scan_link" show:
Broadcaster: defualt_authority Average rate: 17.769 Buffer length: 0.619 Most recent transform: 1688051850.831185 Oldest transform: 1688051850.212133
After shutting down all nodes, and restarting, all branches that go from "base_link" to "scan_link" show:
Broadcaster: defualt_authority Average rate: 16.883 Buffer length: 0.951 Most recent transform: 1688053650.594053 Oldest transform: 1688053649.643528
Asked by Farbod on 2023-06-29 10:52:23 UTC
May I know if base_link
to scan_link
is supposed to change? i.e. is the lidar moving? Nevertheless, what is the CPU usage like (see htop/ rqt_tf_top)? Could it be that there is bottleneck in calculating the tf
s?
Asked by Guess Giant on 2023-06-30 04:10:45 UTC
Thanks so much for the great ideas that help to get to the bottom of this.
In general, the base_link to scan_link transformation can change, i.e., the lidar can move. However, we are not moving the scan_link with respect to the base_link during navigation and/or mapping. I will check into the CPU usage and get back to you with the result in a couple of days, as I am away from the robot at this time.
Thanks again for all the great help.
Asked by Farbod on 2023-07-03 09:14:55 UTC
I checked the CPU usage using htop. During the first couple of minutes after all nav2 nodes are run, none of them use more than 20%-25%. Oddly, after the system runs for a couple of minutes, the two nav2_controller and nav2_planner use 110%-120% CPU. The robot is using a Jetson Xavier, which has 8 CPU cores. Two of them are stuck at 100% at all times (again after a couple of minutes running). The node robot_state_publisher only uses 3.3% CPU, which is (if I am not mistaken) in charge of publishing the /tf and /tf_static topics.
Asked by Farbod on 2023-07-05 12:17:23 UTC
Comments
Just a quick comment: Foxy is EOL. Nav2 on Foxy does not see any updates, and is in fact already quite far behind Humble and Rolling. If you can, I would recommend upgrading. Don't do it in place (so don't remove your Foxy setup), but get a second SSD / SD card / something so you can install
22.04
and Humble on it. Or if you can / are comfortable with it: use Docker.If the same problems occur with newer versions, it would at least be possible to revert to your older system.
Asked by gvdhoorn on 2023-06-28 02:40:15 UTC
I will give that a try by using a second SSD card. I haven't used Docker before. Thanks.
Asked by Farbod on 2023-06-28 11:44:30 UTC