Nav2 Navigation Stack - kilted  kilted
ROS 2 Navigation Stack
round_robin_node.cpp
1 // Copyright (c) 2019 Intel Corporation
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 <string>
16 
17 #include "nav2_behavior_tree/plugins/control/round_robin_node.hpp"
18 
19 namespace nav2_behavior_tree
20 {
21 
22 RoundRobinNode::RoundRobinNode(const std::string & name)
23 : BT::ControlNode::ControlNode(name, {})
24 {
25 }
26 
28  const std::string & name,
29  const BT::NodeConfiguration & config)
30 : BT::ControlNode(name, config)
31 {
32 }
33 
34 BT::NodeStatus RoundRobinNode::tick()
35 {
36  const auto num_children = children_nodes_.size();
37 
38  setStatus(BT::NodeStatus::RUNNING);
39  unsigned num_skipped_children = 0;
40 
41  while (num_failed_children_ + num_skipped_children < num_children) {
42  TreeNode * child_node = children_nodes_[current_child_idx_];
43  const BT::NodeStatus child_status = child_node->executeTick();
44 
45  if (child_status != BT::NodeStatus::RUNNING) {
46  // Increment index and wrap around to the first child
47  if (++current_child_idx_ == num_children) {
48  current_child_idx_ = 0;
49  }
50  }
51 
52  switch (child_status) {
53  case BT::NodeStatus::SUCCESS:
54  {
55  num_failed_children_ = 0;
56  ControlNode::haltChildren();
57  return BT::NodeStatus::SUCCESS;
58  }
59 
60  case BT::NodeStatus::FAILURE:
61  {
62  num_failed_children_++;
63  break;
64  }
65 
66  case BT::NodeStatus::SKIPPED:
67  {
68  num_skipped_children++;
69  break;
70  }
71  case BT::NodeStatus::RUNNING:
72  return BT::NodeStatus::RUNNING;
73 
74  default:
75  throw BT::LogicError("Invalid status return from BT node");
76  }
77  }
78 
79  const bool all_skipped = (num_skipped_children == num_children);
80  halt();
81  // If all the children were skipped, this node is considered skipped
82  return all_skipped ? BT::NodeStatus::SKIPPED : BT::NodeStatus::FAILURE;
83 }
84 
86 {
87  ControlNode::halt();
88  current_child_idx_ = 0;
89  num_failed_children_ = 0;
90 }
91 
92 } // namespace nav2_behavior_tree
93 
94 BT_REGISTER_NODES(factory)
95 {
96  factory.registerNodeType<nav2_behavior_tree::RoundRobinNode>("RoundRobin");
97 }
Type of sequence node that ticks children in a round-robin fashion.
void halt() override
The other (optional) override required by a BT action to reset node state.
BT::NodeStatus tick() override
The main override required by a BT action.
RoundRobinNode(const std::string &name)
A constructor for nav2_behavior_tree::RoundRobinNode.