diff --git a/.codespell_words b/.codespell_words index 38fa9ffbea..41573c032a 100644 --- a/.codespell_words +++ b/.codespell_words @@ -4,3 +4,4 @@ implementors retuned segway lightening +statics diff --git a/configuration/packages/configuring-bt-navigator.rst b/configuration/packages/configuring-bt-navigator.rst index 58f0cb9270..a93b760b5c 100644 --- a/configuration/packages/configuring-bt-navigator.rst +++ b/configuration/packages/configuring-bt-navigator.rst @@ -113,6 +113,18 @@ Parameters Default timeout value (in milliseconds) while a BT action node is waiting for acknowledgement from an action server. This value will be overwritten for a BT node if the input port "server_timeout" is provided. +:default_cancel_timeout: + + ==== ======= + Type Default + ---- ------- + int 50 + ==== ======= + + Description + Default timeout (in seconds) for BT action node cancellation requests during node halt. + This value will be overwritten for a BT node if the input port "cancel_timeout" is provided. + :wait_for_service_timeout: ==== ======= @@ -406,6 +418,8 @@ Example robot_base_frame: base_link transform_tolerance: 0.1 filter_duration: 0.3 + default_server_timeout: 20 + default_cancel_timeout: 50 introspection_mode: "disabled" default_nav_to_pose_bt_xml: replace/with/path/to/bt.xml # or $(find-pkg-share my_package)/behavior_tree/my_nav_to_pose_bt.xml default_nav_through_poses_bt_xml: replace/with/path/to/bt.xml # or $(find-pkg-share my_package)/behavior_tree/my_nav_through_poses_bt.xml diff --git a/migration/Kilted.rst b/migration/Kilted.rst index 7904be63ec..74b7109919 100644 --- a/migration/Kilted.rst +++ b/migration/Kilted.rst @@ -789,3 +789,10 @@ Key parameters: This goal checker is particularly useful for applications requiring precise alignment along specific axes, such as docking operations or warehouse navigation where lateral precision differs from forward/backward precision. See :ref:`configuring_nav2_controller_axis_goal_checker_plugin` for full configuration details. + +New default_cancel_timeout parameter in bt_navigator +---------------------------------------------------- + +In `PR 5895 `_, a new `default_cancel_timeout` parameter was introduced to address timeout issues during action cancellation, such as ``Failed to get result for follow_path in node halt!``. + +The default value is set to `50` milliseconds, and should be adjusted based on the planning time and overall system performance.