diff --git a/behavior_trees/trees/follow_point.rst b/behavior_trees/trees/follow_point.rst
index ea94292c8..beacf0c21 100644
--- a/behavior_trees/trees/follow_point.rst
+++ b/behavior_trees/trees/follow_point.rst
@@ -28,13 +28,13 @@ This behavior tree will execute infinitely in time until the navigation request
-
+
-
+
diff --git a/behavior_trees/trees/nav_through_poses_recovery.rst b/behavior_trees/trees/nav_through_poses_recovery.rst
index aff6f3826..f3bcb62ec 100644
--- a/behavior_trees/trees/nav_through_poses_recovery.rst
+++ b/behavior_trees/trees/nav_through_poses_recovery.rst
@@ -47,7 +47,7 @@ While this behavior tree does not make use of it, the ``PlannerSelector``, ``Con
-
+
@@ -56,7 +56,7 @@ While this behavior tree does not make use of it, the ``PlannerSelector``, ``Con
-
+
@@ -75,9 +75,9 @@ While this behavior tree does not make use of it, the ``PlannerSelector``, ``Con
-
+
-
+
diff --git a/behavior_trees/trees/nav_to_pose_and_pause_near_goal_obstacle.rst b/behavior_trees/trees/nav_to_pose_and_pause_near_goal_obstacle.rst
index 204d5e6e5..31e1fd76b 100644
--- a/behavior_trees/trees/nav_to_pose_and_pause_near_goal_obstacle.rst
+++ b/behavior_trees/trees/nav_to_pose_and_pause_near_goal_obstacle.rst
@@ -1,38 +1,38 @@
Navigate To Pose and Pause Near Goal-Obstacle
#############################################
-.. note:: As a prerequisite, we encourage the users to go through the `Behavior Tree documentation `_, which explains about different behaviors nodes used in these trees such as ``ReactiveSequence``, ``SequenceStar`` and ``RetryUntilSucessfull``.
+.. note:: As a prerequisite, we encourage the users to go through the `Behavior Tree documentation `_, which explains about different behaviors nodes used in these trees such as ``ReactiveSequence``, ``SequenceStar`` and ``RetryUntilSucessfull``.
-This behavior tree is a soft extension to the :ref:`behavior_tree_nav_to_pose`.
+This behavior tree is a soft extension to the :ref:`behavior_tree_nav_to_pose`.
Apart from the functionalities of :ref:`behavior_tree_nav_to_pose`, this behavior tree allows the robot to efficiently handle an obstacle (e.g. forklift, person, or other temporary obstacles) close to the goal by pausing the robot's navigation and wait for a user-specified time to check if the obstacle has cleared.
If the obstacle has moved during the waiting time, the robot will continue to the goal taking the shorter path. If the obstacle has not moved during the waiting time or the waiting time expires, then the robot will use the longer path around to reach the final goal location.
-Ultimately, for a given task, this behavior tree aids in solving the problem of long cycle time, which is caused because of the long path generated due to the temporary obstacles present close to the goal location.
+Ultimately, for a given task, this behavior tree aids in solving the problem of long cycle time, which is caused because of the long path generated due to the temporary obstacles present close to the goal location.
-The behavior tree is depicted in the image below.
-From the image, it can be noted that there is an additional branch in the Navigation Subtree known as ``MonitorAndFollowPath``. This branch is created with the intention for the users to perform any kind of monitoring behavior that their robot should exhibit.
-In this particular BT, the monitoring branch is exclusively utilized by ``PathLongerOnApproach`` BT node for checking if the global planner has decided to plan a significantly longer path for the robot on approaching the user-specified goal proximity.
-If there is no significantly longer path, the monitor node goes into the ``FollowPath`` recovery node, which then generates the necessary control commands.
+The behavior tree is depicted in the image below.
+From the image, it can be noted that there is an additional branch in the Navigation Subtree known as ``MonitorAndFollowPath``. This branch is created with the intention for the users to perform any kind of monitoring behavior that their robot should exhibit.
+In this particular BT, the monitoring branch is exclusively utilized by ``PathLongerOnApproach`` BT node for checking if the global planner has decided to plan a significantly longer path for the robot on approaching the user-specified goal proximity.
+If there is no significantly longer path, the monitor node goes into the ``FollowPath`` recovery node, which then generates the necessary control commands.
.. image:: ../images/walkthrough/patience_and_recovery.png
Once there is a significantly longer path, the child node for the ``PathLongerOnApproach`` node ticks.
-The child node is a ``RetryUntilSuccesfull`` decorator node, which inturns have a ``SequenceStar`` node as its child.
-Firstly, the ``SequenceStar`` node cancels the controller server by ticking the ``CancelControl`` node. The cancellation of the controller server halts the further navigation of the robot.
-Next, the ``SequenceStar`` node ticks the ``Wait`` node, which enables the robot to wait for the given user-specified time.
+The child node is a ``RetryUntilSuccesfull`` decorator node, which inturns have a ``SequenceStar`` node as its child.
+Firstly, the ``SequenceStar`` node cancels the controller server by ticking the ``CancelControl`` node. The cancellation of the controller server halts the further navigation of the robot.
+Next, the ``SequenceStar`` node ticks the ``Wait`` node, which enables the robot to wait for the given user-specified time.
Here we need to note that, the ``MonitorAndFollowPath`` is a ``ReactiveSequence`` node, therefore the ``PathLongerOnApproach`` node needs to return SUCCESS, before the ``FollowPath`` node can be ticked once again.
-In the below GIF, it can be seen that the robot is approaching the goal location, but it found an obstacle in the goal proximity, because of which the global planner, plans a longer path around.
-This is the point where the ``PathLongerOnApproach`` ticks and ticks its children, consequently cancelling the ``controller_server`` and waiting to see if the obstacle clears up.
-In the below scenario, the obstacles do not clear, causing the robot to take the longer path.
+In the below GIF, it can be seen that the robot is approaching the goal location, but it found an obstacle in the goal proximity, because of which the global planner, plans a longer path around.
+This is the point where the ``PathLongerOnApproach`` ticks and ticks its children, consequently cancelling the ``controller_server`` and waiting to see if the obstacle clears up.
+In the below scenario, the obstacles do not clear, causing the robot to take the longer path.
.. image:: ../../migration/images/nav2_patience_near_goal_and_go_around.gif
-Alternatively, if the obstacles are cleared, then there is a shorter path generated by the global planner.
+Alternatively, if the obstacles are cleared, then there is a shorter path generated by the global planner.
Now, the ``PathLongerOnApproach`` returns SUCCESS, that cause the ``FollowPath`` to continue with the robot navigation.
.. image:: ../../migration/images/nav2_patience_near_goal_and_clear_obstacle.gif
-Apart from the above scenarios, we also need to note that, the robot will take the longer path to the goal location if the obstacle does not clear up in the given user-specific wait time.
+Apart from the above scenarios, we also need to note that, the robot will take the longer path to the goal location if the obstacle does not clear up in the given user-specific wait time.
In conclusion, this particular BT would serve, both as an example and ready-to-use BT for an organizational specific application, that wishes to optimize its process cycle time.
@@ -46,7 +46,7 @@ In conclusion, this particular BT would serve, both as an example and ready-to-u
-
+
@@ -60,7 +60,7 @@ In conclusion, this particular BT would serve, both as an example and ready-to-u
-
+
@@ -72,9 +72,9 @@ In conclusion, this particular BT would serve, both as an example and ready-to-u
-
+
-
+
diff --git a/behavior_trees/trees/nav_to_pose_recovery.rst b/behavior_trees/trees/nav_to_pose_recovery.rst
index d1f825d36..48b7d8aa3 100644
--- a/behavior_trees/trees/nav_to_pose_recovery.rst
+++ b/behavior_trees/trees/nav_to_pose_recovery.rst
@@ -42,7 +42,7 @@ While this behavior tree does not make use of it, the ``PlannerSelector``, ``Con
-
+
@@ -50,7 +50,7 @@ While this behavior tree does not make use of it, the ``PlannerSelector``, ``Con
-
+
@@ -69,9 +69,9 @@ While this behavior tree does not make use of it, the ``PlannerSelector``, ``Con
-
+
-
+
diff --git a/behavior_trees/trees/nav_to_pose_with_consistent_replanning_and_if_path_becomes_invalid.rst b/behavior_trees/trees/nav_to_pose_with_consistent_replanning_and_if_path_becomes_invalid.rst
index fd9e7be62..202978a8b 100644
--- a/behavior_trees/trees/nav_to_pose_with_consistent_replanning_and_if_path_becomes_invalid.rst
+++ b/behavior_trees/trees/nav_to_pose_with_consistent_replanning_and_if_path_becomes_invalid.rst
@@ -45,13 +45,13 @@ While this behavior tree does not make use of it, the ``PlannerSelector``, ``Con
-
+
-
+
@@ -62,9 +62,9 @@ While this behavior tree does not make use of it, the ``PlannerSelector``, ``Con
-
+
-
+
diff --git a/configuration/packages/bt-plugins/actions/AssistedTeleop.rst b/configuration/packages/bt-plugins/actions/AssistedTeleop.rst
index 8f9effa22..dd7ed9a3a 100644
--- a/configuration/packages/bt-plugins/actions/AssistedTeleop.rst
+++ b/configuration/packages/bt-plugins/actions/AssistedTeleop.rst
@@ -44,7 +44,7 @@ Input Ports
====== =======
Description
- Action server name.
+ Action server name.
:server_timeout:
@@ -55,22 +55,34 @@ Input Ports
====== =======
Description
- Action server timeout (ms).
+ Action server timeout (ms).
:error_code_id:
============== =======
Type Default
-------------- -------
- uint16 N/A
+ uint16 N/A
============== =======
Description
- Assisted teleop error code. See ``AssistedTeleop`` action message for the enumerated set of error codes.
+ Assisted teleop error code. See ``AssistedTeleop`` action message for the enumerated set of error codes.
+
+:error_msg:
+
+ ============== =======
+ Type Default
+ -------------- -------
+ uint16 N/A
+ ============== =======
+
+ Description
+ Assisted teleop error message. See ``AssistedTeleop`` action message for the enumerated set of error codes.
Example
-------
.. code-block:: xml
-
+
diff --git a/configuration/packages/bt-plugins/actions/BackUp.rst b/configuration/packages/bt-plugins/actions/BackUp.rst
index c3b66c4da..0ba7b61cd 100644
--- a/configuration/packages/bt-plugins/actions/BackUp.rst
+++ b/configuration/packages/bt-plugins/actions/BackUp.rst
@@ -21,7 +21,7 @@ Input Ports
====== =======
Description
- Total distance to backup (m).
+ Total distance to backup (m).
:backup_speed:
@@ -32,7 +32,7 @@ Input Ports
====== =======
Description
- Backup speed (m/s).
+ Backup speed (m/s).
:time_allowance:
@@ -54,7 +54,7 @@ Input Ports
====== =======
Description
- Action server name.
+ Action server name.
:server_timeout:
@@ -65,7 +65,7 @@ Input Ports
====== =======
Description
- Action server timeout (ms).
+ Action server timeout (ms).
Output Ports
------------
@@ -75,15 +75,27 @@ Output Ports
============== =======
Type Default
-------------- -------
- uint16 N/A
+ uint16 N/A
============== =======
Description
- Backup error code. See ``BackUp`` action message for the enumerated set of error codes.
+ Backup error code. See ``BackUp`` action message for the enumerated set of error codes.
+
+:error_msg:
+
+ ============== =======
+ Type Default
+ -------------- -------
+ string N/A
+ ============== =======
+
+ Description
+ Backup error message. See ``BackUp`` action message for the enumerated set of error codes.
Example
-------
.. code-block:: xml
-
+
diff --git a/configuration/packages/bt-plugins/actions/ComputeCoveragePath.rst b/configuration/packages/bt-plugins/actions/ComputeCoveragePath.rst
index c95a0b624..51eb0daf2 100644
--- a/configuration/packages/bt-plugins/actions/ComputeCoveragePath.rst
+++ b/configuration/packages/bt-plugins/actions/ComputeCoveragePath.rst
@@ -3,7 +3,7 @@
ComputeCoveragePath
===================
-Invokes the ComputeCoveragePath ROS 2 action server, which is implemented by the opennav_coverage_ server module.
+Invokes the ComputeCoveragePath ROS 2 action server, which is implemented by the opennav_coverage_ server module.
The server address can be remapped using the ``server_name`` input port.
This server can take in both cartesian and GPS coordinates and is implemented using the ``Fields2Cover`` library.
@@ -16,44 +16,44 @@ Input Ports
===================================== =======
Type Default
------------------------------------- -------
- bool true
+ bool true
===================================== =======
Description
- Whether or not to generate a headland of the field or polygon to compute coverage of
-
+ Whether or not to generate a headland of the field or polygon to compute coverage of
+
:generate_route:
============================================= =======
Type Default
--------------------------------------------- -------
- bool true
+ bool true
============================================= =======
Description
- Whether or not to generate a route, e.g. an ordered set of swaths
+ Whether or not to generate a route, e.g. an ordered set of swaths
:generate_path:
============== =======
Type Default
-------------- -------
- bool true
+ bool true
============== =======
Description
- Whether or not to generate a path, e.g. adding path connectors to the ordered route
+ Whether or not to generate a path, e.g. adding path connectors to the ordered route
:file_field:
============== =======
Type Default
-------------- -------
- string N/A
+ string N/A
============== =======
Description
- The filepath to the field's GML file to use, if not specifying the field via ``polygons``
+ The filepath to the field's GML file to use, if not specifying the field via ``polygons``
:file_field_id:
@@ -61,18 +61,18 @@ Input Ports
============== =======
Type Default
-------------- -------
- int 0
+ int 0
============== =======
Description
- The ID of the field in the GML File to use, if multiple exist in the same file. This is the ordered number of the fields in the file.
+ The ID of the field in the GML File to use, if multiple exist in the same file. This is the ordered number of the fields in the file.
:polygons:
=================================== =======
Type Default
----------------------------------- -------
- vector N/A
+ vector N/A
=================================== =======
Description
@@ -83,12 +83,12 @@ Input Ports
=================================== =======
Type Default
----------------------------------- -------
- string "map"
+ string "map"
=================================== =======
Description
The polygon's frame ID, since the GML file provides the frame ID for its format, this is the frame ID for user-defined input ``polygons``.
-
+
Output Ports
------------
@@ -97,18 +97,18 @@ Output Ports
========================== =======
Type Default
-------------------------- -------
- nav_msgs::msg::Path N/A
+ nav_msgs::msg::Path N/A
========================== =======
Description
- Path created by action server in the form of a navigation path. Takes in a blackboard variable, e.g. "{path}".
+ Path created by action server in the form of a navigation path. Takes in a blackboard variable, e.g. "{path}".
:coverage_path:
========================== =======
Type Default
-------------------------- -------
- vector N/A
+ vector N/A
========================== =======
Description
@@ -119,17 +119,28 @@ Output Ports
============== =======
Type Default
-------------- -------
- uint16 N/A
+ uint16 N/A
+ ============== =======
+
+ Description
+ Compute coverage error code. See ``ComputeCoveragePath`` action message for the enumerated set of error codes.
+
+:error_msg:
+
+ ============== =======
+ Type Default
+ -------------- -------
+ string N/A
============== =======
Description
- Compute coverage error code. See ``ComputeCoveragePath`` action message for the enumerated set of error codes.
+ Compute coverage error message. See ``ComputeCoveragePath`` action message for the enumerated set of error codes.
Example
-------
.. code-block:: xml
-
+
-Note: the blackboard IDs for the path, error code, and more may be adjusted,but need to match the corresponding parameters in the ``CoverageNavigator`` plugin to set on the blackboard for use from the action server.
+Note: the blackboard IDs for the path, error code, and more may be adjusted, but need to match the corresponding parameters in the ``CoverageNavigator`` plugin to set on the blackboard for use from the action server.
diff --git a/configuration/packages/bt-plugins/actions/ComputePathThroughPoses.rst b/configuration/packages/bt-plugins/actions/ComputePathThroughPoses.rst
index beb384c1e..8d6bb754f 100644
--- a/configuration/packages/bt-plugins/actions/ComputePathThroughPoses.rst
+++ b/configuration/packages/bt-plugins/actions/ComputePathThroughPoses.rst
@@ -3,7 +3,7 @@
ComputePathThroughPoses
=======================
-Invokes the ComputePathThroughPoses ROS 2 action server, which is implemented by the nav2_planner_ module.
+Invokes the ComputePathThroughPoses ROS 2 action server, which is implemented by the nav2_planner_ module.
The server address can be remapped using the ``server_name`` input port.
.. _nav2_planner: https://github.com/ros-planning/navigation2/tree/main/nav2_planner
@@ -15,18 +15,18 @@ Input Ports
===================================== =======
Type Default
------------------------------------- -------
- geometry_msgs::msg::PoseStamped N/A
+ geometry_msgs::msg::PoseStamped N/A
===================================== =======
Description
Start pose. Optional. Only used if not left empty. Takes in a blackboard variable, e.g. "{start}".
-
+
:goals:
============================================= =======
Type Default
--------------------------------------------- -------
- vector N/A
+ vector N/A
============================================= =======
Description
@@ -37,7 +37,7 @@ Input Ports
============== =======
Type Default
-------------- -------
- string N/A
+ string N/A
============== =======
Description
@@ -48,7 +48,7 @@ Input Ports
============== =======
Type Default
-------------- -------
- string N/A
+ string N/A
============== =======
Description
@@ -60,12 +60,12 @@ Input Ports
============== =======
Type Default
-------------- -------
- double 10
+ double 10
============== =======
Description
Action server timeout (ms).
-
+
Output Ports
------------
@@ -74,7 +74,7 @@ Output Ports
========================== =======
Type Default
-------------------------- -------
- nav_msgs::msg::Path N/A
+ nav_msgs::msg::Path N/A
========================== =======
Description
@@ -85,15 +85,26 @@ Output Ports
============== =======
Type Default
-------------- -------
- uint16 N/A
+ uint16 N/A
============== =======
Description
Compute path through poses error code. See ``ComputePathThroughPoses`` action message for the enumerated set of error codes.
+:error_msg:
+
+ ============== =======
+ Type Default
+ -------------- -------
+ string N/A
+ ============== =======
+
+ Description
+ Compute path through poses error message. See ``ComputePathThroughPoses`` action message for the enumerated set of error codes.
+
Example
-------
.. code-block:: xml
-
+
diff --git a/configuration/packages/bt-plugins/actions/ComputePathToPose.rst b/configuration/packages/bt-plugins/actions/ComputePathToPose.rst
index 7117273d1..4c4c27087 100644
--- a/configuration/packages/bt-plugins/actions/ComputePathToPose.rst
+++ b/configuration/packages/bt-plugins/actions/ComputePathToPose.rst
@@ -3,7 +3,7 @@
ComputePathToPose
=================
-Invokes the ComputePathToPose ROS 2 action server, which is implemented by the nav2_planner_ module.
+Invokes the ComputePathToPose ROS 2 action server, which is implemented by the nav2_planner_ module.
The server address can be remapped using the ``server_name`` input port.
.. _nav2_planner: https://github.com/ros-planning/navigation2/tree/main/nav2_planner
@@ -15,44 +15,44 @@ Input Ports
===================================== =======
Type Default
------------------------------------- -------
- geometry_msgs::msg::PoseStamped N/A
+ geometry_msgs::msg::PoseStamped N/A
===================================== =======
Description
- Start pose. Optional. Only used if not left empty. Takes in a blackboard variable, e.g. "{start}".
-
+ Start pose. Optional. Only used if not left empty. Takes in a blackboard variable, e.g. "{start}".
+
:goal:
===================================== =======
Type Default
------------------------------------- -------
- geometry_msgs::msg::PoseStamped N/A
+ geometry_msgs::msg::PoseStamped N/A
===================================== =======
Description
- Goal pose. Takes in a blackboard variable, e.g. "{goal}".
+ Goal pose. Takes in a blackboard variable, e.g. "{goal}".
:planner_id:
============== =======
Type Default
-------------- -------
- string N/A
+ string N/A
============== =======
Description
- Mapped name to the planner plugin type to use, e.g. GridBased.
+ Mapped name to the planner plugin type to use, e.g. GridBased.
:server_name:
============== =======
Type Default
-------------- -------
- string N/A
+ string N/A
============== =======
Description
- Action server name.
+ Action server name.
:server_timeout:
@@ -60,12 +60,12 @@ Input Ports
============== =======
Type Default
-------------- -------
- double 10
+ double 10
============== =======
Description
- Action server timeout (ms).
-
+ Action server timeout (ms).
+
Output Ports
------------
@@ -74,26 +74,38 @@ Output Ports
========================== =======
Type Default
-------------------------- -------
- nav_msgs::msg::Path N/A
+ nav_msgs::msg::Path N/A
========================== =======
Description
- Path created by action server. Takes in a blackboard variable, e.g. "{path}".
+ Path created by action server. Takes in a blackboard variable, e.g. "{path}".
:error_code_id:
============== =======
Type Default
-------------- -------
- uint16 N/A
+ uint16 N/A
+ ============== =======
+
+ Description
+ Compute path to pose error code. See ``ComputePathToPose`` action message for the enumerated set of error codes.
+
+:error_msg:
+
+ ============== =======
+ Type Default
+ -------------- -------
+ string N/A
============== =======
Description
- Compute path to pose error code. See ``ComputePathToPose`` action message for the enumerated set of error codes.
+ Compute path to pose error message. See ``ComputePathToPose`` action message for the enumerated set of error codes.
Example
-------
.. code-block:: xml
-
+
diff --git a/configuration/packages/bt-plugins/actions/DockRobot.rst b/configuration/packages/bt-plugins/actions/DockRobot.rst
index 74864555d..e14101df0 100644
--- a/configuration/packages/bt-plugins/actions/DockRobot.rst
+++ b/configuration/packages/bt-plugins/actions/DockRobot.rst
@@ -19,7 +19,7 @@ Input Ports
==== =======
Description
- Whether to use the dock's ID or dock pose fields.
+ Whether to use the dock's ID or dock pose fields.
:dock_id:
@@ -30,7 +30,7 @@ Input Ports
====== =======
Description
- Dock ID or name to use.
+ Dock ID or name to use.
:dock_pose:
@@ -41,7 +41,7 @@ Input Ports
========================= =======
Description
- The dock pose, if not using dock id.
+ The dock pose, if not using dock id.
:dock_type:
@@ -52,7 +52,7 @@ Input Ports
====== =======
Description
- The dock plugin type, if using dock pose.
+ The dock plugin type, if using dock pose.
:max_staging_time:
@@ -63,7 +63,7 @@ Input Ports
===== =======
Description
- Maximum time to navigate to the staging pose.
+ Maximum time to navigate to the staging pose.
:navigate_to_staging_pose:
@@ -74,7 +74,7 @@ Input Ports
==== =======
Description
- Whether to autonomously navigate to staging pose.
+ Whether to autonomously navigate to staging pose.
Output Ports
------------
@@ -88,18 +88,29 @@ Output Ports
==== =======
Description
- If the action was successful.
+ If the action was successful.
:error_code_id:
============== =======
Type Default
-------------- -------
- uint16 0
+ uint16 0
============== =======
Description
- Dock robot error code. See ``DockRobot`` action message for the enumerated set of error codes.
+ Dock robot error code. See ``DockRobot`` action message for the enumerated set of error codes.
+
+:error_msg:
+
+ ============== =======
+ Type Default
+ -------------- -------
+ string 0
+ ============== =======
+
+ Description
+ Dock robot error message. See ``DockRobot`` action message for the enumerated set of error codes.
:num_retries:
@@ -110,11 +121,11 @@ Output Ports
====== =======
Description
- The number of retries executed.
+ The number of retries executed.
Example
-------
.. code-block:: xml
-
+
diff --git a/configuration/packages/bt-plugins/actions/DriveOnHeading.rst b/configuration/packages/bt-plugins/actions/DriveOnHeading.rst
index 0f66028f0..31bf4e9d7 100644
--- a/configuration/packages/bt-plugins/actions/DriveOnHeading.rst
+++ b/configuration/packages/bt-plugins/actions/DriveOnHeading.rst
@@ -20,7 +20,7 @@ Input Ports
====== =======
Description
- Distance to travel (m).
+ Distance to travel (m).
:speed:
@@ -31,7 +31,7 @@ Input Ports
====== =======
Description
- Speed at which to travel (m/s).
+ Speed at which to travel (m/s).
:time_allowance:
@@ -53,7 +53,7 @@ Input Ports
====== =======
Description
- Action server name.
+ Action server name.
:server_timeout:
@@ -64,7 +64,7 @@ Input Ports
====== =======
Description
- Action server timeout (ms).
+ Action server timeout (ms).
Output Ports
------------
@@ -74,15 +74,27 @@ Output Ports
============== =======
Type Default
-------------- -------
- uint16 N/A
+ uint16 N/A
============== =======
Description
- Drive on heading error code. See ``DriveOnHeading`` action message for the enumerated set of error codes.
+ Drive on heading error code. See ``DriveOnHeading`` action message for the enumerated set of error codes.
+
+:error_msg:
+
+ ============== =======
+ Type Default
+ -------------- -------
+ string N/A
+ ============== =======
+
+ Description
+ Drive on heading error message. See ``DriveOnHeading`` action message for the enumerated set of error codes.
Example
-------
.. code-block:: xml
-
+
diff --git a/configuration/packages/bt-plugins/actions/FollowPath.rst b/configuration/packages/bt-plugins/actions/FollowPath.rst
index b596a02d9..1babe054c 100644
--- a/configuration/packages/bt-plugins/actions/FollowPath.rst
+++ b/configuration/packages/bt-plugins/actions/FollowPath.rst
@@ -3,7 +3,7 @@
FollowPath
==========
-Invokes the FollowPath ROS 2 action server, which is implemented by the controller plugin modules loaded.
+Invokes the FollowPath ROS 2 action server, which is implemented by the controller plugin modules loaded.
The server address can be remapped using the ``server_name`` input port.
Input Ports
@@ -14,44 +14,44 @@ Input Ports
====== =======
Type Default
------ -------
- string N/A
+ string N/A
====== =======
Description
- Takes in a blackboard variable containing the path to follow, eg. "{path}".
+ Takes in a blackboard variable containing the path to follow, eg. "{path}".
:controller_id:
====== =======
Type Default
------ -------
- string N/A
+ string N/A
====== =======
Description
- Mapped name of the controller plugin type to use, e.g. FollowPath.
+ Mapped name of the controller plugin type to use, e.g. FollowPath.
:goal_checker_id:
====== =======
Type Default
------ -------
- string N/A
+ string N/A
====== =======
Description
- Mapped name of the goal checker plugin type to use, e.g. SimpleGoalChecker.
+ Mapped name of the goal checker plugin type to use, e.g. SimpleGoalChecker.
:server_name:
====== =======
Type Default
------ -------
- string N/A
+ string N/A
====== =======
Description
- Action server name.
+ Action server name.
:server_timeout:
@@ -59,11 +59,11 @@ Input Ports
============== =======
Type Default
-------------- -------
- double 10
+ double 10
============== =======
Description
- Action server timeout (ms).
+ Action server timeout (ms).
Output Ports
@@ -74,15 +74,27 @@ Output Ports
============== =======
Type Default
-------------- -------
- uint16 N/A
+ uint16 N/A
============== =======
Description
- Follow path error code. See ``FollowPath`` action for the enumerated set of error code definitions.
+ Follow path error code. See ``FollowPath`` action for the enumerated set of error code definitions.
+
+:error_msg:
+
+ ============== =======
+ Type Default
+ -------------- -------
+ string N/A
+ ============== =======
+
+ Description
+ Follow path error message. See ``FollowPath`` action for the enumerated set of error code definitions.
+
Example
-------
.. code-block:: xml
-
+
diff --git a/configuration/packages/bt-plugins/actions/NavigateThroughPoses.rst b/configuration/packages/bt-plugins/actions/NavigateThroughPoses.rst
index 6adcb00ec..b32cd5ec4 100644
--- a/configuration/packages/bt-plugins/actions/NavigateThroughPoses.rst
+++ b/configuration/packages/bt-plugins/actions/NavigateThroughPoses.rst
@@ -15,7 +15,7 @@ Input Ports
============================================= =======
Type Default
--------------------------------------------- -------
- vector N/A
+ vector N/A
============================================= =======
Description
@@ -26,33 +26,33 @@ Input Ports
====== =======
Type Default
------ -------
- string N/A
+ string N/A
====== =======
Description
- Action server name.
+ Action server name.
:server_timeout:
====== =======
Type Default
------ -------
- double 10
+ double 10
====== =======
Description
- Action server timeout (ms).
+ Action server timeout (ms).
:behavior_tree:
====== =======
Type Default
------ -------
- string N/A
+ string N/A
====== =======
Description
- Behavior tree absolute path. If none is specified, NavigateThroughPoses action server uses a default behavior tree.
+ Behavior tree absolute path. If none is specified, NavigateThroughPoses action server uses a default behavior tree.
Output Ports
------------
@@ -62,16 +62,28 @@ Output Ports
============== =======
Type Default
-------------- -------
- uint16 N/A
+ uint16 N/A
============== =======
Description
- The lowest error code in the list of the `error_code_names` parameter.
+ The lowest error code in the list of the `error_code_names` parameter.
+
+:error_msg:
+
+ ============== =======
+ Type Default
+ -------------- -------
+ string N/A
+ ============== =======
+
+ Description
+ The error message associated with the lowest error code in the list of the `error_code_name_prefixes` parameter.
Example
-------
.. code-block:: xml
-
diff --git a/configuration/packages/bt-plugins/actions/NavigateToPose.rst b/configuration/packages/bt-plugins/actions/NavigateToPose.rst
index 1d51a7a27..2eb7fea17 100644
--- a/configuration/packages/bt-plugins/actions/NavigateToPose.rst
+++ b/configuration/packages/bt-plugins/actions/NavigateToPose.rst
@@ -15,44 +15,44 @@ Input Ports
=========== =======
Type Default
----------- -------
- PoseStamped N/A
+ PoseStamped N/A
=========== =======
Description
- Takes in a blackboard variable containing the goal, eg. "{goal}".
+ Takes in a blackboard variable containing the goal, eg. "{goal}".
:server_name:
====== =======
Type Default
------ -------
- string N/A
+ string N/A
====== =======
Description
- Action server name.
+ Action server name.
:server_timeout:
====== =======
Type Default
------ -------
- double 10
+ double 10
====== =======
Description
- Action server timeout (ms).
+ Action server timeout (ms).
:behavior_tree:
====== =======
Type Default
------ -------
- string N/A
+ string N/A
====== =======
Description
- Behavior tree absolute path. If none is specified, NavigateToPose action server uses a default behavior tree.
+ Behavior tree absolute path. If none is specified, NavigateToPose action server uses a default behavior tree.
Output Ports
------------
@@ -62,16 +62,28 @@ Output Ports
============== =======
Type Default
-------------- -------
- uint16 N/A
+ uint16 N/A
============== =======
Description
- The lowest error code in the list of the `error_code_names` parameter.
+ The lowest error code in the list of the `error_code_names` parameter.
+
+:error_msg:
+
+ ============== =======
+ Type Default
+ -------------- -------
+ string N/A
+ ============== =======
+
+ Description
+ The error messages associated with the lowest error code in the list of the `error_code_name_prefixes` parameter.
Example
-------
.. code-block:: xml
-
diff --git a/configuration/packages/bt-plugins/actions/Smooth.rst b/configuration/packages/bt-plugins/actions/Smooth.rst
index f5514e570..92f5d7b16 100644
--- a/configuration/packages/bt-plugins/actions/Smooth.rst
+++ b/configuration/packages/bt-plugins/actions/Smooth.rst
@@ -17,7 +17,7 @@ Input Ports
====== =======
Description
- The blackboard variable or hard-coded input path to smooth
+ The blackboard variable or hard-coded input path to smooth
:max_smoothing_duration:
@@ -35,22 +35,22 @@ Input Ports
====== =======
Type Default
------ -------
- bool false
+ bool false
====== =======
Description
- Whether to check the output smoothed path for collisions.
+ Whether to check the output smoothed path for collisions.
:smoother_id:
====== =======
Type Default
------ -------
- string N/A
+ string N/A
====== =======
Description
- The smoother plugin ID to use for smoothing in the smoother server
+ The smoother plugin ID to use for smoothing in the smoother server
Output Ports
------------
@@ -60,7 +60,7 @@ Output Ports
====== =======
Type Default
------ -------
- string N/A
+ string N/A
====== =======
Description
@@ -71,7 +71,7 @@ Output Ports
====== =======
Type Default
------ -------
- double N/A
+ double N/A
====== =======
Description
@@ -82,7 +82,7 @@ Output Ports
====== =======
Type Default
------ -------
- bool N/A
+ bool N/A
====== =======
Description
@@ -93,15 +93,26 @@ Output Ports
============== =======
Type Default
-------------- -------
- uint16 N/A
+ uint16 N/A
+ ============== =======
+
+ Description
+ Follow smoother error code. See ``SmoothPath`` action for the enumerated set of error code definitions.
+
+:error_msg:
+
+ ============== =======
+ Type Default
+ -------------- -------
+ string N/A
============== =======
Description
- Follow smoother error code. See ``SmoothPath`` action for the enumerated set of error code definitions.
+ Follow smoother error message. See ``SmoothPath`` action for the enumerated set of error code definitions.
Example
-------
.. code-block:: xml
-
+
diff --git a/configuration/packages/bt-plugins/actions/Spin.rst b/configuration/packages/bt-plugins/actions/Spin.rst
index ed382943a..951ae6eed 100644
--- a/configuration/packages/bt-plugins/actions/Spin.rst
+++ b/configuration/packages/bt-plugins/actions/Spin.rst
@@ -21,7 +21,7 @@ Input Ports
====== =======
Description
- Spin distance (radians).
+ Spin distance (radians).
:time_allowance:
@@ -43,7 +43,7 @@ Input Ports
====== =======
Description
- Action server name.
+ Action server name.
:server_timeout:
@@ -54,7 +54,7 @@ Input Ports
====== =======
Description
- Action server timeout (ms).
+ Action server timeout (ms).
:is_recovery:
@@ -65,7 +65,7 @@ Input Ports
==== =======
Description
- True if the action is being used as a recovery.
+ True if the action is being used as a recovery.
Output Ports
------------
@@ -75,16 +75,28 @@ Output Ports
============== =======
Type Default
-------------- -------
- uint16 N/A
+ uint16 N/A
============== =======
Description
- Spin error code. See ``Spin`` action message for the enumerated set of error codes.
+ Spin error code. See ``Spin`` action message for the enumerated set of error codes.
+
+:error_msg:
+
+ ============== =======
+ Type Default
+ -------------- -------
+ string N/A
+ ============== =======
+
+ Description
+ Spin error message. See ``Spin`` action message for the enumerated set of error codes.
Example
-------
.. code-block:: xml
-
+
diff --git a/configuration/packages/bt-plugins/actions/UndockRobot.rst b/configuration/packages/bt-plugins/actions/UndockRobot.rst
index 6125d305e..c9089cb7c 100644
--- a/configuration/packages/bt-plugins/actions/UndockRobot.rst
+++ b/configuration/packages/bt-plugins/actions/UndockRobot.rst
@@ -19,7 +19,7 @@ Input Ports
====== =======
Description
- The dock plugin type, if not previous instance used for docking.
+ The dock plugin type, if not previous instance used for docking.
:max_undocking_time:
@@ -30,7 +30,7 @@ Input Ports
===== =======
Description
- Maximum time to get back to the staging pose.
+ Maximum time to get back to the staging pose.
Output Ports
------------
@@ -44,22 +44,33 @@ Output Ports
==== =======
Description
- If the action was successful.
+ If the action was successful.
:error_code_id:
============== =======
Type Default
-------------- -------
- uint16 0
+ uint16 0
============== =======
Description
- Dock robot error code. See ``UndockRobot`` action message for the enumerated set of error codes.
+ Dock robot error code. See ``UndockRobot`` action message for the enumerated set of error codes.
+
+:error_msg:
+
+ ============== =======
+ Type Default
+ -------------- -------
+ string 0
+ ============== =======
+
+ Description
+ Dock robot error message. See ``UndockRobot`` action message for the enumerated set of error codes.
Example
-------
.. code-block:: xml
-
+
diff --git a/migration/Humble.rst b/migration/Humble.rst
index 550bf9966..cdba722dc 100644
--- a/migration/Humble.rst
+++ b/migration/Humble.rst
@@ -73,13 +73,13 @@ The following errors codes are supported (with more to come as necessary): Unkno
The following error codes are supported (with more to come as necessary): Unknown, TF Error, Invalid Path, Patience Exceeded, Failed To Make Progress, or No Valid Control.
-`PR #3251 `_ pipes the highest priority error code through the bt_navigator and defines the error code structure.
+`PR #3251 `_ pipes the highest priority error code through the bt_navigator and defines the error code structure.
-A new parameter for the the BT Navigator called "error_code_id_names" was added to the nav2_params.yaml to define the error codes to compare.
+A new parameter for the the BT Navigator called "error_code_id_names" was added to the nav2_params.yaml to define the error codes to compare.
The lowest error in the "error_code_id_names" is then returned in the action request (navigate to pose, navigate through poses waypoint follower), whereas the code enums increase the higher up in the software stack - giving higher priority to lower-level failures.
-The error codes produced from the servers follow the guidelines stated below.
-Error codes from 0 to 9999 are reserved for nav2 while error codes from 10000-65535 are reserved for external servers.
+The error codes produced from the servers follow the guidelines stated below.
+Error codes from 0 to 9999 are reserved for nav2 while error codes from 10000-65535 are reserved for external servers.
Each server has two "reserved" error codes. 0 is reserved for NONE and the first error code in the sequence is reserved for UNKNOWN.
The current implemented servers with error codes are:
@@ -112,21 +112,21 @@ Changes to Map yaml file path for map_server node in Launch
SmootherSelector BT Node
************************
-`PR #3283 `_ adds a BT node to set the smoother based on a topic or a default. See the configuration guide :ref:`configuring_simple_smoother` for more details.
+`PR #3283 `_ adds a BT node to set the smoother based on a topic or a default. See the configuration guide :ref:`configuring_simple_smoother` for more details.
-Publish Costmap Layers
+Publish Costmap Layers
**********************
`PR #3320 `_ adds the ability for the nav2_costmap_2d package to publish out costmap data associated with each layer.
Give Behavior Server Access to Both Costmaps
********************************************
-`PR #3255 `_ adds the ability for a behavior to access the local and global costmap.
+`PR #3255 `_ adds the ability for a behavior to access the local and global costmap.
To update behaviors, any reference to the global_frame must be updated to the local_frame parameter
along with the ``configuration`` method which now takes in the local and global collision checkers.
Lastly, ``getResourceInfo`` must be overridden to return ``CostmapInfoType::LOCAL``. Other options include ``GLOBAL`` if the behavior useses global costmap and/or footprint)
-or ``BOTH`` if both are required. This allows us to only create and maintain the minimum amount of expensive resources.
+or ``BOTH`` if both are required. This allows us to only create and maintain the minimum amount of expensive resources.
New Model Predictive Path Integral Controller
*********************************************
@@ -137,20 +137,20 @@ See the README.md and :ref:`configuring_mppic` page for more detail.
Behavior Tree Uses Error Codes
******************************
-`PR #3324 `_ adds three new condition nodes to check for error codes on the blackboard set by action BT nodes which contain them.
+`PR #3324 `_ adds three new condition nodes to check for error codes on the blackboard set by action BT nodes which contain them.
-The ``AreErrorCodesPresent`` condition node allows the user to specify the error code from the server along with the error codes to match against.
-The ``WouldAControllerRecoveryHelp`` checks if the active error code is UNKNOWN, PATIENCE_EXCEEDED, FAILED_TO_MAKE_PROGRESS or NO_VALID_CONTROL.
+The ``AreErrorCodesPresent`` condition node allows the user to specify the error code from the server along with the error codes to match against.
+The ``WouldAControllerRecoveryHelp`` checks if the active error code is UNKNOWN, PATIENCE_EXCEEDED, FAILED_TO_MAKE_PROGRESS or NO_VALID_CONTROL.
If the error code is a match, the condition returns ``SUCCESS``.
-These error code are potentially able to be cleared by a controller recovery.
+These error code are potentially able to be cleared by a controller recovery.
The ``WouldAPlannerRecoveryHelp`` checks if the active error code is UNKNOWN, NO_VALID_CONTROL, or TIMEOUT.
If the error code is a match, the condition returns ``SUCCESS``.
-These error code are potentially able to be cleared by a planner recovery.
+These error code are potentially able to be cleared by a planner recovery.
The ``WouldASmootherRecoveryHelp`` checks if the active error code is UNKNOWN, TIMEOUT, FAILED_TO_SMOOTH_PATH, or SMOOTHED_PATH_IN_COLLISION.
If the error code is a match, the condition returns ``SUCCESS``.
-These error code are potentially able to be cleared by a smoother recovery.
+These error code are potentially able to be cleared by a smoother recovery.
Load, Save and Loop Waypoints from the Nav2 Panel in RViz
*********************************************************
@@ -203,11 +203,11 @@ Beware that it is a breaking change and that configuration files will need to be
IsBatteryChargingCondition BT Node
**********************************
-`PR #3553 `_ adds a BT node to check if the battery is charging. See the configuration guide :ref:`bt_is_battery_charging_condition` for more details.
+`PR #3553 `_ adds a BT node to check if the battery is charging. See the configuration guide :ref:`bt_is_battery_charging_condition` for more details.
-Behavior Server Error Codes
+Behavior Server Error Codes
***************************
-`PR #3569 `_ updates the behavior server plugins to provide error codes on failure.
+`PR #3569 `_ updates the behavior server plugins to provide error codes on failure.
- Spin: NONE: 0, UNKNOWN: 701, server error codes: 701-709
- BackUp: NONE: 0, UNKNOWN: 801, server error codes: 710-719
diff --git a/migration/Jazzy.rst b/migration/Jazzy.rst
index 72797814b..361128ca8 100644
--- a/migration/Jazzy.rst
+++ b/migration/Jazzy.rst
@@ -5,6 +5,20 @@ Jazzy to K-Turtle
Moving from ROS 2 Jazzy to K-Turtle, a number of stability improvements were added that we will not specifically address here.
+BehaviorTree error_msg
+**********************
+
+`PR #4459 https://github.com/ros-navigation/navigation2/pull/4459>`_ adds error_msg to all action result messages
+`PR #4460 `_ captures and propagates error_msg result strings through the bt_navigator.
+
+A new parameter for the BT Navigator "error_code_name_prefixes" was introduced. It replaces the "error_code_id_names" parameter to support both an error code and an associated error message. Behavior tree elements that support an "error_code_id" and "error_msg" attribute, must have values that use the corresponding prefix with the suffix "_error_code" and "_error_msg" respectively. The error messages can then be viewed by applications calling Nav2 or its servers for handling specific errors with more contextual information than simply the error code.
+
+Thus, users must update their ``nav2_params.yaml`` to include this new format of specifying error message and code locations.
+
+.. code-block:: xml
+
+
+
New Nav2 Loopback Simulator
***************************
@@ -80,4 +94,5 @@ Before:
After:
-.. image:: images/fix_flickering_visualization_after.png
\ No newline at end of file
+.. image:: images/fix_flickering_visualization_after.png
+
diff --git a/tutorials/docs/adding_a_nav2_task_server.rst b/tutorials/docs/adding_a_nav2_task_server.rst
index 9f8e78e9a..870ebee39 100644
--- a/tutorials/docs/adding_a_nav2_task_server.rst
+++ b/tutorials/docs/adding_a_nav2_task_server.rst
@@ -1,9 +1,9 @@
.. _adding_a_nav2_task_server:
-Adding a New Nav2 Task Server
+Adding a New Nav2 Task Server
#############################
-A nav2 task server consists of server side logic to complete different types of requests, usually called by the autonomy system or through the Behavior Tree Navigator. In this guide, we will discuss the core components needed to add a new task server to Nav2 (ex. Controller, Behavior, Smoother, Planner Servers). Namely, how to set up your new Lifecycle-Component Node for launch and state management and the communication of semantically meaningful error codes (if necessary).
+A nav2 task server consists of server side logic to complete different types of requests, usually called by the autonomy system or through the Behavior Tree Navigator. In this guide, we will discuss the core components needed to add a new task server to Nav2 (ex. Controller, Behavior, Smoother, Planner Servers). Namely, how to set up your new Lifecycle-Component Node for launch and state management and the communication of semantically meaningful error codes (if necessary).
While this tutorial does not cover how to add the complementary Behavior Tree Node to interact with this new Task Server, that is covered at length in :ref:`writing_new_nbt_plugin` so this Task Server can be invoked in the BTs in BT Navigator.
@@ -107,12 +107,12 @@ We make use of the launch files to compose different servers into a single proce
nav2_route_server
-Error codes
+Error codes
***********
-Your nav2 task server may also wish to return a 'error_code' in its action response (though not required). If there are semantically meaningful and actionable types of failures for your system, this is a systemic way to communicate those failures which may be automatically aggregated into the responses of the navigation system to your application.
+Your nav2 task server may also wish to return a 'error_code' and 'error_msg' in its action response (though not required). If there are semantically meaningful and actionable types of failures for your system, this is a systemic way to communicate those failures which may be automatically aggregated into the responses of the navigation system to your application.
-It is important to note that error codes from 0-9999 are reserved for internal nav2 servers with each server offset by 100 while external servers start at 10000 and end at 65535.
+It is important to note that error codes from 0-9999 are reserved for internal nav2 servers with each server offset by 100 while external servers start at 10000 and end at 65535.
The table below shows the current servers along with the expected error code structure.
@@ -153,8 +153,7 @@ The table below shows the current servers along with the expected error code str
.. _Waypoint Follower Server: https://github.com/ros-planning/navigation2/blob/main/nav2_waypoint_follower/src/waypoint_follower.cpp
.. _Behavior Server: https://github.com/ros-planning/navigation2/blob/main/nav2_behaviors/src/behavior_server.cpp
-Error codes are attached to the response of the action message. An example can be seen below for the route server. Note that by convention we set the error code field within the message definition to ``error_code``.
-
+Error codes and messages are attached to the response of the action message. An example can be seen below for the route server. Note it is necessary to set the error code field within the message result definition to ``error_code`` and the error message field to ``error_msg``.
.. code-block:: bash
@@ -177,22 +176,22 @@ Error codes are attached to the response of the action message. An example can b
nav_msgs/Route route
builtin_interfaces/Duration route_time
uint16 error_code
+ string error_msg
---
-As stated in the message, the priority order of the errors should match the message order, 0 is reserved for NONE and the first error code in the sequence is reserved for UNKNOWN.
+As stated in the message, the priority order of the errors codes should match the message order, 0 is reserved for NONE and the first error code in the sequence is reserved for UNKNOWN.
Since the the route server is a external server, the errors codes start at 10000 and go up to 10099.
-In order to propagate your server's error code to the rest of the system it must be added to the nav2_params.yaml file.
-The `error_code_id_names` inside of the BT Navigator define what error codes to look for on the blackboard by the server. The lowest error code of the sequence is then returned - whereas the code enums increase the higher up in the software stack - giving higher priority to lower-level failures.
-
+To ensure your server's error codes, and associated error messages, are properly communicated throughout the system, you need to configure them in your nav2_params.yaml file.
+The BT Navigator parameter `error_code_name_prefixes` defines a list of prefixes used to search the behavior tree blackboard, for the existence and content of error codes and error messages keys, that may have been generated. If the blackboard contains multiple error code keys then the lowest error code value of the sequence, and associated error message, is then returned in the result of the navigator action message. Error code enums increase the higher up they occur in the software stack. In other words higher priority is given to reporting lower-level failures.
.. code-block:: yaml
- error_code_id_names:
- - compute_path_error_code_id
- - follow_path_error_code_id
- - route_error_code_id
+ error_code_name_prefixes:
+ - compute_path
+ - follow_path
+ - route
Conclusion
**********
diff --git a/tutorials/docs/adding_smoother.rst b/tutorials/docs/adding_smoother.rst
index 7d17a2979..cb8045bbf 100644
--- a/tutorials/docs/adding_smoother.rst
+++ b/tutorials/docs/adding_smoother.rst
@@ -38,7 +38,7 @@ Please see the BT node's configuration page to familiarize yourself with all asp
1- Specifying a Smoother Plugin
-------------------------------
-In order to use a smoother in your BT node, you must first configure the smoother server itself to contain the smoother plugins of interest. These plugins implement the specific algorithms that you would like to use.
+In order to use a smoother in your BT node, you must first configure the smoother server itself to contain the smoother plugins of interest. These plugins implement the specific algorithms that you would like to use.
For each smoother plugin you would like to use, a name must be given to it (e.g. ``simple_smoother``, ``curvature_smoother``). This name is its ``smoother_id`` for other servers to interact with this algorithm from a request to the Smoother Server's action interface.
@@ -68,27 +68,27 @@ Now that you have selected and configured the smoother server for your given plu
Note: If you use only a single type of smoothing algorithm, there is no need to specify the ``smoother_id`` in the BT XML entry. Since there is only a single option, that will be used for any request that does not specifically request a smoother plugin. However, if you leverage multiple smoother plugins, you **must** populate the ``smoother_id`` XML port.
-A given behavior tree will have a line:
+A given behavior tree will have a line:
.. code-block:: xml
-
+
-This line calls the planner server and return a path to the ``path`` blackboard variable in the behavior tree. We are going to replace that line with the following to compute the path, smooth the path, and finally replace the ``path`` blackboard variable with the new smoothed path that the system will now interact with:
+This line calls the planner server and return a path to the ``path`` blackboard variable in the behavior tree. We are going to replace that line with the following to compute the path, smooth the path, and finally replace the ``path`` blackboard variable with the new smoothed path that the system will now interact with:
.. code-block:: xml
-
-
+
+
If you wish to have recoveries for the smoother error codes, such as triggering the system recoveries branch of a behavior tree:
-.. code-block:: xml
+.. code-block:: xml
-
+