Nav2 Navigation Stack - rolling  main
ROS 2 Navigation Stack
recovery_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 #include "nav2_behavior_tree/plugins/control/recovery_node.hpp"
17 
18 namespace nav2_behavior_tree
19 {
20 
22  const std::string & name,
23  const BT::NodeConfiguration & conf)
24 : BT::ControlNode::ControlNode(name, conf),
25  current_child_idx_(0),
26  number_of_retries_(1),
27  retry_count_(0)
28 {
29 }
30 
31 BT::NodeStatus RecoveryNode::tick()
32 {
33  getInput("number_of_retries", number_of_retries_);
34  const unsigned children_count = children_nodes_.size();
35 
36  if (children_count != 2) {
37  throw BT::BehaviorTreeException("Recovery Node '" + name() + "' must only have 2 children.");
38  }
39 
40  setStatus(BT::NodeStatus::RUNNING);
41 
42  while (current_child_idx_ < children_count && retry_count_ <= number_of_retries_) {
43  TreeNode * child_node = children_nodes_[current_child_idx_];
44  const BT::NodeStatus child_status = child_node->executeTick();
45 
46  if (current_child_idx_ == 0) {
47  switch (child_status) {
48  case BT::NodeStatus::SKIPPED:
49  // If first child is skipped, the entire branch is considered skipped
50  halt();
51  return BT::NodeStatus::SKIPPED;
52 
53  case BT::NodeStatus::SUCCESS:
54  // reset node and return success when first child returns success
55  // also halt the recovery action as the main action is successful, reset its state
56  ControlNode::haltChild(1);
57  halt();
58  return BT::NodeStatus::SUCCESS;
59 
60  case BT::NodeStatus::RUNNING:
61  return BT::NodeStatus::RUNNING;
62 
63  case BT::NodeStatus::FAILURE:
64  {
65  if (retry_count_ < number_of_retries_) {
66  // halt first child and tick second child in next iteration
67  ControlNode::haltChild(0);
68  current_child_idx_++;
69  break;
70  } else {
71  // reset node and return failure when max retries has been exceeded
72  halt();
73  return BT::NodeStatus::FAILURE;
74  }
75  }
76 
77  default:
78  throw BT::LogicError("A child node must never return IDLE");
79  } // end switch
80 
81  } else if (current_child_idx_ == 1) {
82  switch (child_status) {
83  case BT::NodeStatus::SKIPPED:
84  {
85  // if we skip the recovery (maybe a precondition fails), then we
86  // should assume that no recovery is possible. For this reason,
87  // we should return FAILURE and reset the index.
88  // This does not count as a retry.
89  current_child_idx_ = 0;
90  ControlNode::haltChild(1);
91  return BT::NodeStatus::FAILURE;
92  }
93  case BT::NodeStatus::RUNNING:
94  return child_status;
95 
96  case BT::NodeStatus::SUCCESS:
97  {
98  // halt second child, increment recovery count, and tick first child in next iteration
99  ControlNode::haltChild(1);
100  retry_count_++;
101  current_child_idx_ = 0;
102  }
103  break;
104 
105  case BT::NodeStatus::FAILURE:
106  // reset node and return failure if second child fails
107  halt();
108  return BT::NodeStatus::FAILURE;
109 
110  default:
111  throw BT::LogicError("A child node must never return IDLE");
112  } // end switch
113  }
114  } // end while loop
115 
116  // reset node and return failure
117  halt();
118  return BT::NodeStatus::FAILURE;
119 }
120 
121 void RecoveryNode::halt()
122 {
123  ControlNode::halt();
124  retry_count_ = 0;
125  current_child_idx_ = 0;
126 }
127 
128 } // namespace nav2_behavior_tree
129 
130 #include "behaviortree_cpp/bt_factory.h"
131 BT_REGISTER_NODES(factory)
132 {
133  factory.registerNodeType<nav2_behavior_tree::RecoveryNode>("RecoveryNode");
134 }
The RecoveryNode has only two children and returns SUCCESS if and only if the first child returns SUC...
RecoveryNode(const std::string &name, const BT::NodeConfiguration &conf)
A constructor for nav2_behavior_tree::RecoveryNode.