Skip to content

Commit f6a11d8

Browse files
aosmwSteveMacenskiewak
authored
Document bt_navigator error_code_name_prefixes and error_msg (#587)
* Trim trailing whitespace Signed-off-by: Mike Wake <[email protected]> * Document behavior tree error_code_name_prefixes, error_msg Signed-off-by: Mike Wake <[email protected]> * address error_msg review comments Signed-off-by: Mike Wake <[email protected]> * Update migration/Jazzy.rst Signed-off-by: Steve Macenski <[email protected]> * Improve mandatory migration for error_code_name_prefixes parameter (#586) Signed-off-by: Mike Wake <[email protected]> * Document navigator error code ranges (#586) Signed-off-by: Mike Wake <[email protected]> * More behavior tree error_msg migration clarity (#586) Signed-off-by: Mike Wake <[email protected]> * Add builtin error_code_name_prefixes to tutorial (#586) Signed-off-by: Mike Wake <[email protected]> * Some more s/error_code_names/error_code_name_prefixes (#586) Signed-off-by: Mike Wake <[email protected]> * Add error_code_id and error_msg to Wait action (#586) Signed-off-by: Mike Wake <[email protected]> * distinguish release for error_code_names and error_code_name_prefixes (#586) error_code_names - Jazzy and older error_code_name_prefixes - Kilted and newer Signed-off-by: Mike Wake <[email protected]> * Expand error code ranges for navigators (#586) Signed-off-by: Mike Wake <[email protected]> * Update configuration/packages/configuring-bt-navigator.rst Signed-off-by: Steve Macenski <[email protected]> * Update configuration/packages/configuring-bt-navigator.rst Signed-off-by: Steve Macenski <[email protected]> * Update migration/Jazzy.rst Signed-off-by: Steve Macenski <[email protected]> * Update Jazzy.rst Signed-off-by: Steve Macenski <[email protected]> --------- Signed-off-by: Mike Wake <[email protected]> Signed-off-by: Steve Macenski <[email protected]> Signed-off-by: Mike Wake <[email protected]> Co-authored-by: Steve Macenski <[email protected]> Co-authored-by: Mike Wake <[email protected]>
1 parent 5eff78d commit f6a11d8

24 files changed

+522
-236
lines changed

behavior_trees/trees/follow_point.rst

Lines changed: 2 additions & 2 deletions
Original file line numberDiff line numberDiff line change
@@ -28,13 +28,13 @@ This behavior tree will execute infinitely in time until the navigation request
2828
<RateController hz="1.0">
2929
<Sequence>
3030
<GoalUpdater input_goal="{goal}" output_goal="{updated_goal}">
31-
<ComputePathToPose goal="{updated_goal}" path="{path}" planner_id="{selected_planner}" error_code_id="{compute_path_error_code}"/>
31+
<ComputePathToPose goal="{updated_goal}" path="{path}" planner_id="{selected_planner}" error_code_id="{compute_path_error_code}" error_msg="{compute_path_error_msg}"/>
3232
</GoalUpdater>
3333
<TruncatePath distance="1.0" input_path="{path}" output_path="{truncated_path}"/>
3434
</Sequence>
3535
</RateController>
3636
<KeepRunningUntilFailure>
37-
<FollowPath path="{truncated_path}" controller_id="{selected_controller}" error_code_id="{follow_path_error_code}"/>
37+
<FollowPath path="{truncated_path}" controller_id="{selected_controller}" error_code_id="{follow_path_error_code}" error_msg="{follow_path_error_msg}"/>
3838
</KeepRunningUntilFailure>
3939
</PipelineSequence>
4040
</BehaviorTree>

behavior_trees/trees/nav_through_poses_recovery.rst

Lines changed: 4 additions & 4 deletions
Original file line numberDiff line numberDiff line change
@@ -47,7 +47,7 @@ While this behavior tree does not make use of it, the ``PlannerSelector``, ``Con
4747
<RecoveryNode number_of_retries="1" name="ComputePathThroughPoses">
4848
<ReactiveSequence>
4949
<RemovePassedGoals input_goals="{goals}" output_goals="{goals}" radius="0.7"/>
50-
<ComputePathThroughPoses goals="{goals}" path="{path}" planner_id="{selected_planner}" error_code_id="{compute_path_error_code}"/>
50+
<ComputePathThroughPoses goals="{goals}" path="{path}" planner_id="{selected_planner}" error_code_id="{compute_path_error_code}" error_msg="{compute_path_error_msg}"/>
5151
</ReactiveSequence>
5252
<Sequence>
5353
<WouldAPlannerRecoveryHelp error_code="{compute_path_error_code}"/>
@@ -56,7 +56,7 @@ While this behavior tree does not make use of it, the ``PlannerSelector``, ``Con
5656
</RecoveryNode>
5757
</RateController>
5858
<RecoveryNode number_of_retries="1" name="FollowPath">
59-
<FollowPath path="{path}" controller_id="{selected_controller}" error_code_id="{follow_path_error_code}"/>
59+
<FollowPath path="{path}" controller_id="{selected_controller}" error_code_id="{follow_path_error_code}" error_msg="{follow_path_error_msg}"/>
6060
<Sequence>
6161
<WouldAControllerRecoveryHelp error_code="{follow_path_error_code}"/>
6262
<ClearEntireCostmap name="ClearLocalCostmap-Context" service_name="local_costmap/clear_entirely_local_costmap"/>
@@ -75,9 +75,9 @@ While this behavior tree does not make use of it, the ``PlannerSelector``, ``Con
7575
<ClearEntireCostmap name="ClearLocalCostmap-Subtree" service_name="local_costmap/clear_entirely_local_costmap"/>
7676
<ClearEntireCostmap name="ClearGlobalCostmap-Subtree" service_name="global_costmap/clear_entirely_global_costmap"/>
7777
</Sequence>
78-
<Spin spin_dist="1.57" error_code_id="{spin_error_code}"/>
78+
<Spin spin_dist="1.57" error_code_id="{spin_error_code} error_msg="{spin_error_msg}"/>
7979
<Wait wait_duration="5.0"/>
80-
<BackUp backup_dist="0.30" backup_speed="0.05" error_code_id="{backup_error_code}"/>
80+
<BackUp backup_dist="0.30" backup_speed="0.05" error_code_id="{backup_error_code}" error_msg="{backup_error_msg}"/>
8181
</RoundRobin>
8282
</ReactiveFallback>
8383
</Sequence>

behavior_trees/trees/nav_to_pose_and_pause_near_goal_obstacle.rst

Lines changed: 15 additions & 15 deletions
Original file line numberDiff line numberDiff line change
@@ -3,15 +3,15 @@ Navigate To Pose and Pause Near Goal-Obstacle
33

44
.. note:: As a prerequisite, we encourage the users to go through the `Behavior Tree documentation <https://behaviortree.github.io/BehaviorTree.CPP/>`_, which explains about different behaviors nodes used in these trees such as ``ReactiveSequence``, ``SequenceWithMemory`` and ``RetryUntilSuccessful``.
55

6-
This behavior tree is a soft extension to the :ref:`behavior_tree_nav_to_pose`.
6+
This behavior tree is a soft extension to the :ref:`behavior_tree_nav_to_pose`.
77
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.
88
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.
9-
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.
9+
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.
1010

11-
The behavior tree is depicted in the image below.
12-
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.
13-
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.
14-
If there is no significantly longer path, the monitor node goes into the ``FollowPath`` recovery node, which then generates the necessary control commands.
11+
The behavior tree is depicted in the image below.
12+
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.
13+
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.
14+
If there is no significantly longer path, the monitor node goes into the ``FollowPath`` recovery node, which then generates the necessary control commands.
1515

1616
.. image:: ../images/walkthrough/patience_and_recovery.png
1717

@@ -21,18 +21,18 @@ Firstly, the ``SequenceWithMemory`` node cancels the controller server by tickin
2121
Next, the ``SequenceWithMemory`` node ticks the ``Wait`` node, which enables the robot to wait for the given user-specified time.
2222
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.
2323

24-
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.
25-
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.
26-
In the below scenario, the obstacles do not clear, causing the robot to take the longer path.
24+
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.
25+
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.
26+
In the below scenario, the obstacles do not clear, causing the robot to take the longer path.
2727

2828
.. image:: ../../migration/images/nav2_patience_near_goal_and_go_around.gif
2929

30-
Alternatively, if the obstacles are cleared, then there is a shorter path generated by the global planner.
30+
Alternatively, if the obstacles are cleared, then there is a shorter path generated by the global planner.
3131
Now, the ``PathLongerOnApproach`` returns SUCCESS, that cause the ``FollowPath`` to continue with the robot navigation.
3232

3333
.. image:: ../../migration/images/nav2_patience_near_goal_and_clear_obstacle.gif
3434

35-
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.
35+
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.
3636

3737
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.
3838

@@ -46,7 +46,7 @@ In conclusion, this particular BT would serve, both as an example and ready-to-u
4646
<PlannerSelector selected_planner="{selected_planner}" default_planner="GridBased" topic_name="planner_selector"/>
4747
<RateController hz="1.0">
4848
<RecoveryNode number_of_retries="1" name="ComputePathToPose">
49-
<ComputePathToPose goal="{goal}" path="{path}" planner_id="{selected_planner}" error_code_id="{compute_path_error_code}"/>
49+
<ComputePathToPose goal="{goal}" path="{path}" planner_id="{selected_planner}" error_code_id="{compute_path_error_code}" error_msg="{compute_path_error_msg}"/>
5050
<ClearEntireCostmap name="ClearGlobalCostmap-Context" service_name="global_costmap/clear_entirely_global_costmap"/>
5151
</RecoveryNode>
5252
</RateController>
@@ -60,7 +60,7 @@ In conclusion, this particular BT would serve, both as an example and ready-to-u
6060
</RetryUntilSuccessful>
6161
</PathLongerOnApproach>
6262
<RecoveryNode number_of_retries="1" name="FollowPath">
63-
<FollowPath path="{path}" controller_id="{selected_controller}" error_code_id="{follow_path_error_code}"/>
63+
<FollowPath path="{path}" controller_id="{selected_controller}" error_code_id="{follow_path_error_code}" error_msg="{follow_path_error_msg}"/>
6464
<ClearEntireCostmap name="ClearLocalCostmap-Context" service_name="local_costmap/clear_entirely_local_costmap"/>
6565
</RecoveryNode>
6666
</ReactiveSequence>
@@ -72,9 +72,9 @@ In conclusion, this particular BT would serve, both as an example and ready-to-u
7272
<ClearEntireCostmap name="ClearLocalCostmap-Subtree" service_name="local_costmap/clear_entirely_local_costmap"/>
7373
<ClearEntireCostmap name="ClearGlobalCostmap-Subtree" service_name="global_costmap/clear_entirely_global_costmap"/>
7474
</Sequence>
75-
<Spin spin_dist="1.57"/>
75+
<Spin spin_dist="1.57" error_code_id="{spin_error_code}" error_msg="{spin_error_msg}"/>
7676
<Wait wait_duration="5.0"/>
77-
<BackUp backup_dist="0.30" backup_speed="0.05"/>
77+
<BackUp backup_dist="0.30" backup_speed="0.05" error_code_id="{backup_error_code}" error_msg="{backup_error_msg}"/>
7878
</RoundRobin>
7979
</ReactiveFallback>
8080
</RecoveryNode>

behavior_trees/trees/nav_to_pose_recovery.rst

Lines changed: 4 additions & 4 deletions
Original file line numberDiff line numberDiff line change
@@ -42,15 +42,15 @@ While this behavior tree does not make use of it, the ``PlannerSelector``, ``Con
4242
<PlannerSelector selected_planner="{selected_planner}" default_planner="GridBased" topic_name="planner_selector"/>
4343
<RateController hz="1.0">
4444
<RecoveryNode number_of_retries="1" name="ComputePathToPose">
45-
<ComputePathToPose goal="{goal}" path="{path}" planner_id="{selected_planner}" error_code_id="{compute_path_error_code}"/>
45+
<ComputePathToPose goal="{goal}" path="{path}" planner_id="{selected_planner}" error_code_id="{compute_path_error_code}" error_msg="{compute_path_error_msg}"/>
4646
<Sequence>
4747
<WouldAPlannerRecoveryHelp error_code="{compute_path_error_code}"/>
4848
<ClearEntireCostmap name="ClearGlobalCostmap-Context" service_name="global_costmap/clear_entirely_global_costmap"/>
4949
</Sequence>
5050
</RecoveryNode>
5151
</RateController>
5252
<RecoveryNode number_of_retries="1" name="FollowPath">
53-
<FollowPath path="{path}" controller_id="{selected_controller}" error_code_id="{follow_path_error_code}"/>
53+
<FollowPath path="{path}" controller_id="{selected_controller}" error_code_id="{follow_path_error_code}" error_msg="{follow_path_error_msg}"/>
5454
<Sequence>
5555
<WouldAControllerRecoveryHelp error_code="{follow_path_error_code}"/>
5656
<ClearEntireCostmap name="ClearLocalCostmap-Context" service_name="local_costmap/clear_entirely_local_costmap"/>
@@ -69,9 +69,9 @@ While this behavior tree does not make use of it, the ``PlannerSelector``, ``Con
6969
<ClearEntireCostmap name="ClearLocalCostmap-Subtree" service_name="local_costmap/clear_entirely_local_costmap"/>
7070
<ClearEntireCostmap name="ClearGlobalCostmap-Subtree" service_name="global_costmap/clear_entirely_global_costmap"/>
7171
</Sequence>
72-
<Spin spin_dist="1.57" error_code_id="{spin_error_code}"/>
72+
<Spin spin_dist="1.57" error_code_id="{spin_error_code}" error_msg="{spin_error_msg}"/>
7373
<Wait wait_duration="5.0"/>
74-
<BackUp backup_dist="0.30" backup_speed="0.05" error_code_id="{backup_code_id}"/>
74+
<BackUp backup_dist="0.30" backup_speed="0.05" error_code_id="{backup_error_code}" error_msg="{backup_error_msg}"/>
7575
</RoundRobin>
7676
</ReactiveFallback>
7777
</Sequence>

behavior_trees/trees/nav_to_pose_with_consistent_replanning_and_if_path_becomes_invalid.rst

Lines changed: 4 additions & 4 deletions
Original file line numberDiff line numberDiff line change
@@ -45,13 +45,13 @@ While this behavior tree does not make use of it, the ``PlannerSelector``, ``Con
4545
</Inverter>
4646
<IsPathValid path="{path}"/>
4747
</ReactiveSequence>
48-
<ComputePathToPose goal="{goal}" path="{path}" planner_id="{selected_planner}" error_code_id="{compute_path_error_code}"/>
48+
<ComputePathToPose goal="{goal}" path="{path}" planner_id="{selected_planner}" error_code_id="{compute_path_error_code}" error_msg="{compute_path_error_msg}"/>
4949
</Fallback>
5050
<ClearEntireCostmap name="ClearGlobalCostmap-Context" service_name="global_costmap/clear_entirely_global_costmap"/>
5151
</RecoveryNode>
5252
</RateController>
5353
<RecoveryNode number_of_retries="1" name="RecoveryFollowPath">
54-
<FollowPath path="{path}" controller_id="{selected_controller}" error_code_id="{follow_path_error_code}"/>
54+
<FollowPath path="{path}" controller_id="{selected_controller}" error_code_id="{follow_path_error_code}" error_msg="{follow_path_error_msg}"/>
5555
<ClearEntireCostmap name="ClearLocalCostmap-Context" service_name="local_costmap/clear_entirely_local_costmap"/>
5656
</RecoveryNode>
5757
</PipelineSequence>
@@ -62,9 +62,9 @@ While this behavior tree does not make use of it, the ``PlannerSelector``, ``Con
6262
<ClearEntireCostmap name="ClearLocalCostmap-Subtree" service_name="local_costmap/clear_entirely_local_costmap"/>
6363
<ClearEntireCostmap name="ClearGlobalCostmap-Subtree" service_name="global_costmap/clear_entirely_global_costmap"/>
6464
</Sequence>
65-
<Spin name="SpinRecovery" spin_dist="1.57"/>
65+
<Spin name="SpinRecovery" spin_dist="1.57" error_code_id="{spin_error_code}" error_msg="{spin_error_msg}"/>
6666
<Wait name="WaitRecovery" wait_duration="5.0"/>
67-
<BackUp name="BackUpRecovery" backup_dist="0.30" backup_speed="0.05"/>
67+
<BackUp name="BackUpRecovery" backup_dist="0.30" backup_speed="0.05" error_code_id="{backup_error_code}" error_msg="{backup_error_msg}"/>
6868
</RoundRobin>
6969
</ReactiveFallback>
7070
</RecoveryNode>

configuration/packages/bt-plugins/actions/AssistedTeleop.rst

Lines changed: 17 additions & 5 deletions
Original file line numberDiff line numberDiff line change
@@ -44,7 +44,7 @@ Input Ports
4444
====== =======
4545

4646
Description
47-
Action server name.
47+
Action server name.
4848

4949
:server_timeout:
5050

@@ -55,22 +55,34 @@ Input Ports
5555
====== =======
5656

5757
Description
58-
Action server timeout (ms).
58+
Action server timeout (ms).
5959

6060
:error_code_id:
6161

6262
============== =======
6363
Type Default
6464
-------------- -------
65-
uint16 N/A
65+
uint16 N/A
6666
============== =======
6767

6868
Description
69-
Assisted teleop error code. See ``AssistedTeleop`` action message for the enumerated set of error codes.
69+
Assisted teleop error code. See ``AssistedTeleop`` action message for the enumerated set of error codes.
70+
71+
:error_msg:
72+
73+
============== =======
74+
Type Default
75+
-------------- -------
76+
uint16 N/A
77+
============== =======
78+
79+
Description
80+
Assisted teleop error message. See ``AssistedTeleop`` action message for the enumerated set of error codes.
7081

7182
Example
7283
-------
7384

7485
.. code-block:: xml
7586
76-
<AssistedTeleop is_recovery="false" server_name="assisted_teleop_server" server_timeout="10" error_code_id="{assisted_teleop_error_code}"/>
87+
<AssistedTeleop is_recovery="false" server_name="assisted_teleop_server" server_timeout="10"
88+
error_code_id="{assisted_teleop_error_code}" error_msg="{assisted_teleop_error_msg}"/>

configuration/packages/bt-plugins/actions/BackUp.rst

Lines changed: 19 additions & 7 deletions
Original file line numberDiff line numberDiff line change
@@ -21,7 +21,7 @@ Input Ports
2121
====== =======
2222

2323
Description
24-
Total distance to backup (m).
24+
Total distance to backup (m).
2525

2626
:backup_speed:
2727

@@ -32,7 +32,7 @@ Input Ports
3232
====== =======
3333

3434
Description
35-
Backup speed (m/s).
35+
Backup speed (m/s).
3636

3737
:time_allowance:
3838

@@ -54,7 +54,7 @@ Input Ports
5454
====== =======
5555

5656
Description
57-
Action server name.
57+
Action server name.
5858

5959
:server_timeout:
6060

@@ -65,7 +65,7 @@ Input Ports
6565
====== =======
6666

6767
Description
68-
Action server timeout (ms).
68+
Action server timeout (ms).
6969

7070
:disable_collision_checks:
7171

@@ -86,15 +86,27 @@ Output Ports
8686
============== =======
8787
Type Default
8888
-------------- -------
89-
uint16 N/A
89+
uint16 N/A
9090
============== =======
9191

9292
Description
93-
Backup error code. See ``BackUp`` action message for the enumerated set of error codes.
93+
Backup error code. See ``BackUp`` action message for the enumerated set of error codes.
94+
95+
:error_msg:
96+
97+
============== =======
98+
Type Default
99+
-------------- -------
100+
string N/A
101+
============== =======
102+
103+
Description
104+
Backup error message. See ``BackUp`` action message for the enumerated set of error codes.
94105

95106
Example
96107
-------
97108

98109
.. code-block:: xml
99110
100-
<BackUp backup_dist="-0.2" backup_speed="0.05" server_name="backup_server" server_timeout="10" error_code_id="{backup_error_code}" disable_collision_checks="false"/>
111+
<BackUp backup_dist="-0.2" backup_speed="0.05" server_name="backup_server" server_timeout="10" disable_collision_checks="false"
112+
error_code_id="{backup_error_code}" error_msg="{backup_error_msg}"/>

0 commit comments

Comments
 (0)