Nav2 Navigation Stack - rolling  main
ROS 2 Navigation Stack
persistent_sequence.cpp
1 // Copyright (c) 2025 Enjoy Robotics
2 //
3 // Licensed under the Apache License, Version 2.0 (the "License");
4 // you may not use this file except in compliance with the License.
5 // You may obtain a copy of the License at
6 //
7 // http://www.apache.org/licenses/LICENSE-2.0
8 //
9 // Unless required by applicable law or agreed to in writing, software
10 // distributed under the License is distributed on an "AS IS" BASIS,
11 // WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
12 // See the License for the specific language governing permissions and
13 // limitations under the License.
14 
15 #include "nav2_behavior_tree/plugins/control/persistent_sequence.hpp"
16 #include "behaviortree_cpp/action_node.h"
17 #include "behaviortree_cpp/bt_factory.h"
18 
19 namespace nav2_behavior_tree
20 {
21 
22 PersistentSequenceNode::PersistentSequenceNode(
23  const std::string & name,
24  const BT::NodeConfiguration & conf)
25 : BT::ControlNode::ControlNode(name, conf) {}
26 
27 BT::NodeStatus PersistentSequenceNode::tick()
28 {
29  const int children_count = children_nodes_.size();
30 
31  int current_child_idx;
32  getInput("current_child_idx", current_child_idx);
33 
34  setStatus(BT::NodeStatus::RUNNING);
35 
36  while (current_child_idx < children_count) {
37  TreeNode * current_child_node = children_nodes_[current_child_idx];
38  const BT::NodeStatus child_status = current_child_node->executeTick();
39 
40  switch (child_status) {
41  case BT::NodeStatus::RUNNING:
42  return child_status;
43 
44  case BT::NodeStatus::FAILURE:
45  // Reset on failure
46  resetChildren();
47  current_child_idx = 0;
48  setOutput("current_child_idx", 0);
49  return child_status;
50 
51  case BT::NodeStatus::SUCCESS:
52  case BT::NodeStatus::SKIPPED:
53  // Skip the child node
54  current_child_idx++;
55  setOutput("current_child_idx", current_child_idx);
56  break;
57 
58  case BT::NodeStatus::IDLE:
59  throw std::runtime_error("A child node must never return IDLE");
60  } // end switch
61  } // end while loop
62 
63  // The entire while loop completed. This means that all the children returned SUCCESS.
64  if (current_child_idx >= children_count) {
65  resetChildren();
66  setOutput("current_child_idx", 0);
67  }
68  return BT::NodeStatus::SUCCESS;
69 }
70 
71 } // namespace nav2_behavior_tree
72 
73 BT_REGISTER_NODES(factory)
74 {
75  BT::NodeBuilder builder =
76  [](const std::string & name, const BT::NodeConfiguration & config)
77  {
78  return std::make_unique<nav2_behavior_tree::PersistentSequenceNode>(
79  name, config);
80  };
81 
82  factory.registerBuilder<nav2_behavior_tree::PersistentSequenceNode>(
83  "PersistentSequence", builder);
84 }
The PersistentSequenceNode is similar to the SequenceNode, but it stores the index of the last runnin...