Skip to content

Commit 2b740c4

Browse files
Write docs for PauseResumeController and PersistentSequence (#739)
* Write docs for PauseResumeController and PersistentSequence Signed-off-by: redvinaa <[email protected]> * Fix typo Signed-off-by: redvinaa <[email protected]> * Update behavior_trees/overview/nav2_specific_nodes.rst Co-authored-by: Steve Macenski <[email protected]> Signed-off-by: Vince Reda <[email protected]> * Update configuration/packages/bt-plugins/controls/PersistentSequence.rst Co-authored-by: Steve Macenski <[email protected]> Signed-off-by: Vince Reda <[email protected]> * Update configuration/packages/bt-plugins/controls/PauseResumeController.rst Co-authored-by: Steve Macenski <[email protected]> Signed-off-by: Vince Reda <[email protected]> * Update configuration/packages/bt-plugins/controls/PauseResumeController.rst Co-authored-by: Steve Macenski <[email protected]> Signed-off-by: Vince Reda <[email protected]> * Update behavior_trees/overview/nav2_specific_nodes.rst Co-authored-by: Steve Macenski <[email protected]> Signed-off-by: Vince Reda <[email protected]> * Update behavior_trees/overview/nav2_specific_nodes.rst Co-authored-by: Steve Macenski <[email protected]> Signed-off-by: Vince Reda <[email protected]> * Add new pages to index Signed-off-by: redvinaa <[email protected]> * Add section about new nodes to migration guide Signed-off-by: redvinaa <[email protected]> --------- Signed-off-by: redvinaa <[email protected]> Signed-off-by: Vince Reda <[email protected]> Co-authored-by: Steve Macenski <[email protected]>
1 parent df02aa0 commit 2b740c4

File tree

7 files changed

+188
-26
lines changed

7 files changed

+188
-26
lines changed

behavior_trees/overview/nav2_specific_nodes.rst

Lines changed: 68 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -315,3 +315,71 @@ To explain this further, here is an example BT that uses NonblockingSequence.
315315
Recall that if ``Action_A``, ``Action_B``, or ``Action_C`` returned ``FAILURE`` at any point of time, the parent would have returned ``FAILURE`` and halted any children as well.
316316

317317
For additional details regarding the ``NonblockingSequence`` please see the `NonblockingSequence configuration guide <../../configuration/packages/bt-plugins/controls/NonblockingSequence.html>`_.
318+
319+
Control: PersistentSequence
320+
----------------------------
321+
322+
The ``PersistentSequence`` is similar to the ``Sequence`` node, but it stores the index of the last running child in the blackboard (key: "current_child_idx"), and it does not reset the index on halt.
323+
324+
For more information see the ``Sequence`` BT node in BT.CPP.
325+
326+
.. code-block:: xml
327+
328+
<root main_tree_to_execute="MainTree">
329+
<BehaviorTree ID="MainTree">
330+
<Script code="current_child_idx := 0" />
331+
<PersistentSequence current_child_idx="{current_child_idx}">
332+
<Action_A/>
333+
<Action_B/>
334+
<Action_C/>
335+
</PersistentSequence>
336+
</BehaviorTree>
337+
</root>
338+
339+
Control: PauseResumeController
340+
------------------------------
341+
342+
The ``PauseResumeController`` is a control node that adds pause and resume functionality to a behavior tree through service calls.
343+
344+
It has one mandatory child for the RESUMED, and three optional for the PAUSED state, the ON_PAUSE event and the ON_RESUME event.
345+
It has two input ports:
346+
347+
- ``pause_service_name``: name of the service to pause
348+
- ``resume_service_name``: name of the service to resume
349+
350+
1. The controller starts in RESUMED state, and ticks it until it returns success.
351+
2. When the pause service is called, ON_PAUSE is ticked until completion, then the controller switches to PAUSED state.
352+
3. In PAUSED state the PAUSED child is ticked until the state is changed, or until it returns failure.
353+
4. When the resume service is called, ON_RESUME is ticked until completion, then the controller switches back to RESUMED state.
354+
355+
The controller only returns success when the RESUMED child returns success. The controller returns failure if any child returns failure. In any other case, it returns running.
356+
357+
.. code-block:: xml
358+
359+
<PauseResumeController pause_service_name="/pause" resume_service_name="/resume">
360+
<!-- RESUMED branch -->
361+
362+
<!-- PAUSED branch (optional) -->
363+
364+
<!-- ON_PAUSE branch (optional) -->
365+
366+
<!-- ON_RESUME branch (optional) -->
367+
</PauseResumeController>
368+
369+
When the ON_PAUSE and ON_RESUME branches fail, the controller will return failure, halt, and the state will be reset to RESUMED. It might be desirable to retry the transition a few times before failing for real, which functionality is not built in the controller node, but is easily achievable by adding a retry node in the BT:
370+
371+
.. code-block:: xml
372+
373+
<PauseResumeController pause_service_name="/pause" resume_service_name="/resume">
374+
<!-- RESUMED branch -->
375+
376+
<!-- PAUSED branch -->
377+
378+
<RetryUntilSuccessful num_attempts="3">
379+
<!-- ON_PAUSE branch -->
380+
</RetryUntilSuccessful>
381+
382+
<RetryUntilSuccessful num_attempts="3">
383+
<!-- ON_RESUME branch -->
384+
</RetryUntilSuccessful>
385+
</PauseResumeController>
Lines changed: 52 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,52 @@
1+
.. _bt_pause_resume_controller_control:
2+
3+
PauseResumeController
4+
===================
5+
6+
Controlled through service calls to pause and resume the execution of the tree.
7+
It has one mandatory child for the RESUMED, and three optional for the PAUSED state, the ON_PAUSE event and the ON_RESUME event.
8+
It has two input ports:
9+
10+
- pause_service_name: name of the service to pause
11+
- resume_service_name: name of the service to resume
12+
13+
The controller starts in RESUMED state, and ticks it until it returns success.
14+
When the pause service is called, ON_PAUSE is ticked until completion, then the controller switches to PAUSED state.
15+
When the resume service is called, ON_RESUME is ticked until completion, then the controller switches back to RESUMED state.
16+
17+
The controller only returns success when the RESUMED child returns success.
18+
The controller returns failure if any child returns failure.
19+
In any other case, it returns running.
20+
21+
Example
22+
-------
23+
24+
.. code-block:: xml
25+
26+
<PauseResumeController pause_service_name="/pause" resume_service_name="/resume">
27+
<!-- RESUMED branch (mandatory) -->
28+
29+
<!-- PAUSED branch (optional) -->
30+
31+
<!-- ON_PAUSE branch (optional) -->
32+
33+
<!-- ON_RESUME branch (optional) -->
34+
</PauseResumeController>
35+
36+
When the ON_PAUSE and ON_RESUME branches fail, the controller will return failure, halt, and the state will be reset to RESUMED. It might be desirable to retry the transition a few times before failing for real, which functionality is not built in the controller node, but is easily achievable by adding a retry node in the BT:
37+
38+
.. code-block:: xml
39+
40+
<PauseResumeController pause_service_name="/pause" resume_service_name="/resume">
41+
<!-- RESUMED branch -->
42+
43+
<!-- PAUSED branch -->
44+
45+
<RetryUntilSuccessful num_attempts="3">
46+
<!-- ON_PAUSE branch -->
47+
</RetryUntilSuccessful>
48+
49+
<RetryUntilSuccessful num_attempts="3">
50+
<!-- ON_RESUME branch -->
51+
</RetryUntilSuccessful>
52+
</PauseResumeController>
Lines changed: 21 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,21 @@
1+
.. _bt_persistent_sequence_control:
2+
3+
PersistentSequence
4+
===================
5+
6+
The PersistentSequenceNode is similar to the SequenceNode, but it stores the index of the last running child in the blackboard (key: `current_child_idx`), and it does not reset the index when it got halted. It used to tick children in an ordered sequence. If any child returns RUNNING, previous children will NOT be ticked again.
7+
This can be helpful paired with the ``PauseResumeController``.
8+
9+
- If all the children return SUCCESS, this node returns SUCCESS.
10+
- If a child returns RUNNING, this node returns RUNNING. Loop is NOT restarted, the same running child will be ticked again.
11+
- If a child returns FAILURE, stop the loop and return FAILURE. Restart the loop only if (reset_on_failure == true)
12+
13+
Example
14+
-------
15+
16+
.. code-block:: xml
17+
18+
<Script code="current_child_idx := 0" />
19+
<PersistentSequence current_child_idx="{current_child_idx}">
20+
<!-- Child nodes here -->
21+
</PersistentSequence>

configuration/packages/configuring-bt-navigator.rst

Lines changed: 2 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -376,6 +376,8 @@ Example
376376
- nav2_speed_controller_bt_node
377377
- nav2_recovery_node_bt_node
378378
- nav2_pipeline_sequence_bt_node
379+
- nav2_persistent_sequence_bt_node
380+
- nav2_pause_resume_controller_bt_node
379381
- nav2_round_robin_node_bt_node
380382
- nav2_transform_available_condition_bt_node
381383
- nav2_time_expired_condition_bt_node

configuration/packages/configuring-bt-xml.rst

Lines changed: 2 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -100,6 +100,8 @@ Control Plugins
100100
bt-plugins/controls/RoundRobin.rst
101101
bt-plugins/controls/RecoveryNode.rst
102102
bt-plugins/controls/NonblockingSequence.rst
103+
bt-plugins/controls/PersistentSequence.rst
104+
bt-plugins/controls/PauseResumeController.rst
103105

104106
Decorator Plugins
105107
*****************

migration/Kilted.rst

Lines changed: 7 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -225,3 +225,10 @@ The MPPI controller now has a plugin, ``OptimalTrajectoryValidator``, which can
225225
This can be used to check for collisions, margin from obstacles, distance from a path, progress being made, etc.
226226
By default, it uses the ``DefaultOptimalTrajectoryValidator`` which checks for collisions.
227227
Note that kinematic and dynamic constraints are not required to be checked as the Optimizer ensures these constraints are met.
228+
229+
Added PersistentSequence and PauseResumeController Control Nodes
230+
****************************************************************
231+
232+
In `PR #5247 <https://github.com/ros-navigation/navigation2/pull/5247>`_ two new Nav2 specific behavior tree control nodes have been added.
233+
234+
The ``PauseResumeController`` (`docs <../configuration/packages/bt-plugins/controls/PauseResumeController.html>`_) adds services to pause and resume execution of the tree. Related to this, the ``PersistentSequence`` (`docs <../configuration/packages/bt-plugins/controls/PersistentSequence.html>`_) control node allows the child index to be exposed to the behavior tree through a bidirectional port. This allows the sequence to be continued on resume where it was paused.

plugins/index.rst

Lines changed: 36 additions & 26 deletions
Original file line numberDiff line numberDiff line change
@@ -641,37 +641,47 @@ Behavior Tree Nodes
641641
.. _PathLongerOnApproach: https://github.com/ros-navigation/navigation2/tree/main/nav2_behavior_tree/plugins/decorator/path_longer_on_approach.cpp
642642
.. _GoalUpdatedController: https://github.com/ros-navigation/navigation2/blob/main/nav2_behavior_tree/plugins/decorator/goal_updated_controller.cpp
643643

644-
+-------------------------+------------------------+----------------------------------+
645-
| Control Plugin Name | Creator | Description |
646-
+=========================+========================+==================================+
647-
| `Pipeline Sequence`_ | Carl Delsey | A variant of a sequence node that|
648-
| | | will re-tick previous children |
649-
| | | even if another child is running |
650-
+-------------------------+------------------------+----------------------------------+
651-
| `Recovery`_ | Carl Delsey | Node must contain 2 children |
652-
| | | and returns success if first |
653-
| | | succeeds. If first fails, the |
654-
| | | second will be ticked. If |
655-
| | | successful, it will retry the |
656-
| | | first and then return its value |
657-
+-------------------------+------------------------+----------------------------------+
658-
| `Round Robin`_ | Mohammad Haghighipanah | Will tick ``i`` th child until |
659-
| | | a result and move on to ``i+1`` |
660-
+-------------------------+------------------------+----------------------------------+
661-
| `Nonblocking Sequence`_ | Alexander Yuen | A variant of a sequence node that|
662-
| | | will tick through the whole |
663-
| | | sequence even if a child returns |
664-
| | | running. On reticks of this |
665-
| | | control node, successful children|
666-
| | | will be ticked once again to |
667-
| | | prevent a stale state from being |
668-
| | | latched. |
669-
+-------------------------+------------------------+----------------------------------+
644+
+----------------------------+------------------------+----------------------------------+
645+
| Control Plugin Name | Creator | Description |
646+
+============================+========================+==================================+
647+
| `Pipeline Sequence`_ | Carl Delsey | A variant of a sequence node that|
648+
| | | will re-tick previous children |
649+
| | | even if another child is running |
650+
+----------------------------+------------------------+----------------------------------+
651+
| `Recovery`_ | Carl Delsey | Node must contain 2 children |
652+
| | | and returns success if first |
653+
| | | succeeds. If first fails, the |
654+
| | | second will be ticked. If |
655+
| | | successful, it will retry the |
656+
| | | first and then return its value |
657+
+----------------------------+------------------------+----------------------------------+
658+
| `Round Robin`_ | Mohammad Haghighipanah | Will tick ``i`` th child until |
659+
| | | a result and move on to ``i+1`` |
660+
+----------------------------+------------------------+----------------------------------+
661+
| `Nonblocking Sequence`_ | Alexander Yuen | A variant of a sequence node that|
662+
| | | will tick through the whole |
663+
| | | sequence even if a child returns |
664+
| | | running. On reticks of this |
665+
| | | control node, successful children|
666+
| | | will be ticked once again to |
667+
| | | prevent a stale state from being |
668+
| | | latched. |
669+
+----------------------------+------------------------+----------------------------------+
670+
| `Persistent Sequence`_ | Enjoy Robotics | A variant of a sequence node that|
671+
| | | exposes ``current_child_idx`` as |
672+
| | | a bidirectional port. |
673+
+----------------------------+------------------------+----------------------------------+
674+
| `Pause Resume Controller`_ | Enjoy Robotics | Controlled through service calls |
675+
| | | to pause and resume the |
676+
| | | execution of the tree. |
677+
+----------------------------+------------------------+----------------------------------+
670678

671679
.. _Pipeline Sequence: https://github.com/ros-navigation/navigation2/tree/main/nav2_behavior_tree/plugins/control/pipeline_sequence.cpp
672680
.. _Recovery: https://github.com/ros-navigation/navigation2/tree/main/nav2_behavior_tree/plugins/control/recovery_node.cpp
673681
.. _Round Robin: https://github.com/ros-navigation/navigation2/tree/main/nav2_behavior_tree/plugins/control/round_robin_node.cpp
674682
.. _Nonblocking Sequence: https://github.com/ros-navigation/navigation2/tree/main/nav2_behavior_tree/plugins/control/nonblocking_sequence.cpp
683+
.. _Persistent Sequence: https://github.com/ros-navigation/navigation2/tree/main/nav2_behavior_tree/plugins/control/persistent_sequence.cpp
684+
.. _Pause Resume Controller: https://github.com/ros-navigation/navigation2/tree/main/nav2_behavior_tree/plugins/control/pause_resume_controller.cpp
675685

676686

677687

0 commit comments

Comments
 (0)