parallel_node.cpp
Go to the documentation of this file.
1 /* Copyright (C) 2015-2018 Michele Colledanchise - All Rights Reserved
2  * Copyright (C) 2018-2020 Davide Faconti, Eurecat - All Rights Reserved
3 *
4 * Permission is hereby granted, free of charge, to any person obtaining a copy of this software and associated documentation files (the "Software"),
5 * to deal in the Software without restriction, including without limitation the rights to use, copy, modify, merge, publish, distribute, sublicense,
6 * and/or sell copies of the Software, and to permit persons to whom the Software is furnished to do so, subject to the following conditions:
7 * The above copyright notice and this permission notice shall be included in all copies or substantial portions of the Software.
8 *
9 * THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY,
10 * FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER LIABILITY,
11 * WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE SOFTWARE.
12 */
13 
14 #include <algorithm>
15 #include <cstddef>
16 
18 
19 namespace BT
20 {
21 constexpr const char* ParallelNode::THRESHOLD_FAILURE;
22 constexpr const char* ParallelNode::THRESHOLD_SUCCESS;
23 
24 ParallelNode::ParallelNode(const std::string& name, int success_threshold,
25  int failure_threshold) :
26  ControlNode::ControlNode(name, {}),
27  success_threshold_(success_threshold),
28  failure_threshold_(failure_threshold),
30 {
31  setRegistrationID("Parallel");
32 }
33 
35  ControlNode::ControlNode(name, config),
39 {}
40 
42 {
44  {
46  {
47  throw RuntimeError("Missing parameter [", THRESHOLD_SUCCESS, "] in ParallelNode");
48  }
49 
51  {
52  throw RuntimeError("Missing parameter [", THRESHOLD_FAILURE, "] in ParallelNode");
53  }
54  }
55 
56  size_t success_childred_num = 0;
57  size_t failure_childred_num = 0;
58 
59  const size_t children_count = children_nodes_.size();
60 
61  if (children_count < successThreshold())
62  {
63  throw LogicError("Number of children is less than threshold. Can never succeed.");
64  }
65 
66  if (children_count < failureThreshold())
67  {
68  throw LogicError("Number of children is less than threshold. Can never fail.");
69  }
70 
71  // Routing the tree according to the sequence node's logic:
72  for (unsigned int i = 0; i < children_count; i++)
73  {
74  TreeNode* child_node = children_nodes_[i];
75 
76  bool in_skip_list = (skip_list_.count(i) != 0);
77 
78  NodeStatus child_status;
79  if (in_skip_list)
80  {
81  child_status = child_node->status();
82  }
83  else
84  {
85  child_status = child_node->executeTick();
86  }
87 
88  switch (child_status)
89  {
90  case NodeStatus::SUCCESS: {
91  if (!in_skip_list)
92  {
93  skip_list_.insert(i);
94  }
95  success_childred_num++;
96 
97  if (success_childred_num == successThreshold())
98  {
99  skip_list_.clear();
100  resetChildren();
101  return NodeStatus::SUCCESS;
102  }
103  }
104  break;
105 
106  case NodeStatus::FAILURE: {
107  if (!in_skip_list)
108  {
109  skip_list_.insert(i);
110  }
111  failure_childred_num++;
112 
113  // It fails if it is not possible to succeed anymore or if
114  // number of failures are equal to failure_threshold_
115  if ((failure_childred_num > children_count - successThreshold()) ||
116  (failure_childred_num == failureThreshold()))
117  {
118  skip_list_.clear();
119  resetChildren();
120  return NodeStatus::FAILURE;
121  }
122  }
123  break;
124 
125  case NodeStatus::RUNNING: {
126  // do nothing
127  }
128  break;
129 
130  default: {
131  throw LogicError("A child node must never return IDLE");
132  }
133  }
134  }
135 
136  return NodeStatus::RUNNING;
137 }
138 
140 {
141  skip_list_.clear();
143 }
144 
146 {
147  return success_threshold_ < 0 ?
148  std::max(children_nodes_.size() + success_threshold_ + 1, size_t(0)) :
150 }
151 
153 {
154  return failure_threshold_ < 0 ?
155  std::max(children_nodes_.size() + failure_threshold_ + 1, size_t(0)) :
157 }
158 
160 {
161  success_threshold_ = threshold_M;
162 }
163 
165 {
166  failure_threshold_ = threshold_M;
167 }
168 
169 } // namespace BT
size_t failureThreshold() const
std::vector< TreeNode * > children_nodes_
Definition: control_node.h:24
virtual void halt() override
const NodeConfiguration & config() const
Definition: tree_node.cpp:127
NodeStatus status() const
Definition: tree_node.cpp:84
static constexpr const char * THRESHOLD_SUCCESS
Definition: parallel_node.h:72
ParallelNode(const std::string &name, int success_threshold, int failure_threshold=1)
static constexpr const char * THRESHOLD_FAILURE
Definition: parallel_node.h:73
const std::string & name() const
Name of the instance, not the type.
Definition: tree_node.cpp:101
std::set< int > skip_list_
Definition: parallel_node.h:69
bool read_parameter_from_ports_
Definition: parallel_node.h:71
void setSuccessThreshold(int threshold_M)
Result getInput(const std::string &key, T &destination) const
Definition: tree_node.h:232
virtual void halt() override
Abstract base class for Behavior Tree Nodes.
Definition: tree_node.h:55
void setFailureThreshold(int threshold_M)
void setRegistrationID(StringView ID)
Definition: tree_node.cpp:201
size_t successThreshold() const
virtual BT::NodeStatus tick() override
Method to be implemented by the user.
NodeStatus
Definition: basic_types.h:35
virtual BT::NodeStatus executeTick()
The method that should be used to invoke tick() and setStatus();.
Definition: tree_node.cpp:32


behaviortree_cpp_v3
Author(s): Michele Colledanchise, Davide Faconti
autogenerated on Mon Jul 3 2023 02:50:14