Path planning error - ROS2 Navigation course

Laura, it happens that the course is teaching you the Nav2 for Galactic, but the project is based on Foxy. This means that some things we teach for Galactic are not available for Foxy.

For instance, the default bt XML file parameter has been changed from default_bt_xml_filename in Foxy to default_nav_to_pose_bt_xml in Galactic.

Also, there are some plugin_lib_names that do not exist in Foxy.

Those differences between ROS2 versions can produce strange errors. So let me provide you with a Foxy example of config files that you can use to compare with yours.

For the BT Navigator

bt_navigator:
  ros__parameters:
    use_sim_time: True
    global_frame: map
    robot_base_frame: base_link
    odom_topic: /odom
    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

Behavior XML:

<root main_tree_to_execute="MainTree">
  <BehaviorTree ID="MainTree">
    <RecoveryNode number_of_retries="6" name="NavigateRecovery">
      <PipelineSequence name="NavigateWithReplanning">
        <RateController hz="1.0">
          <RecoveryNode number_of_retries="1" name="ComputePathToPose">
            <ComputePathToPose goal="{goal}" path="{path}" planner_id="GridBased"/>
            <ClearEntireCostmap name="ClearGlobalCostmap-Context" service_name="global_costmap/clear_entirely_global_costmap"/>
          </RecoveryNode>
        </RateController>
        <RecoveryNode number_of_retries="1" name="FollowPath">
          <FollowPath path="{path}" controller_id="FollowPath"/>
          <ClearEntireCostmap name="ClearLocalCostmap-Context" service_name="local_costmap/clear_entirely_local_costmap"/>
        </RecoveryNode>
      </PipelineSequence>
      <ReactiveFallback name="RecoveryFallback">
        <GoalUpdated/>
        <SequenceStar name="RecoveryActions">
          <ClearEntireCostmap name="ClearLocalCostmap-Subtree" service_name="local_costmap/clear_entirely_local_costmap"/>
          <ClearEntireCostmap name="ClearGlobalCostmap-Subtree" service_name="global_costmap/clear_entirely_global_costmap"/>
          <Spin spin_dist="1.57"/>
          <Wait wait_duration="5"/>
        </SequenceStar>
      </ReactiveFallback>
    </RecoveryNode>
  </BehaviorTree>
</root>

The error Action server failed while executing action callback: "send_goal failed", according to this post by the Nav2 creator, that is an error that only happens on Nav2 for Foxy, so it is solved in Galactic. Do not worry about it, since the error is not actually preventing the robot to reach the goal

About the error Control loop missed its desired rate of 10.0000Hz this means that the controller server cannot compute everything at 10Hz, as you indicated in the controller.yaml file parameter controller_frequency: 10.0.
This is due to the computer not being able to handle all the load. This is an important error message because it means two things:

  1. Either you requested a too fast control loop (your robot may not require that high control speed). If that is the case, you can just decrease the value of the parameter and it will be ok
  2. Given the speed at which your robot moves, you need at least that control frequency, otherwise the robot can crash. In that case, you need to decrease both the controller_frequency parameter but also the maximum speeds at which your robot can move, so, by decreasing the control loop frequency, your robot will not crash. In this case you need to play with the following parameters of the controller.yaml
      min_vel_x: 0.0
      min_vel_y: 0.0
      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
      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

About the error

[rviz2-8] rviz2: /tmp/binarydeb/ros-foxy-rviz-ogre-vendor-8.2.3/obj-x86_64-linux-gnu/ogre-v1.12.1-prefix/src/ogre-v1.12.1/OgreMain/src/OgreNode.cpp:626: void Ogre::Node::setScale(const Vector3&): Assertion `!inScale.isNaN() && "Invalid vector supplied as parameter"' failed.

Do not worry, is not preventing you from using Rviz.
Rviz is not that stable, so you should experience some crashes from time to time. That is why you must save your Rviz configuration.

3 Likes