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 
15 
16 namespace BT
17 {
18 
19 constexpr const char* ParallelNode::THRESHOLD_FAILURE;
20 constexpr const char* ParallelNode::THRESHOLD_SUCCESS;
21 
22 ParallelNode::ParallelNode(const std::string& name, unsigned success_threshold,
23  unsigned failure_threshold)
24  : ControlNode::ControlNode(name, {} ),
25  success_threshold_(success_threshold),
26  failure_threshold_(failure_threshold),
28 {
29  setRegistrationID("Parallel");
30 }
31 
32 ParallelNode::ParallelNode(const std::string &name,
34  : ControlNode::ControlNode(name, config),
38 {
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 < success_threshold_)
62  {
63  throw LogicError("Number of children is less than threshold. Can never succeed.");
64  }
65 
66  if( children_count < failure_threshold_)
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  child_status = child_node->executeTick();
85  }
86 
87  switch (child_status)
88  {
90  {
91  if( !in_skip_list )
92  {
93  skip_list_.insert(i);
94  }
95  success_childred_num++;
96 
97  if (success_childred_num == success_threshold_)
98  {
99  skip_list_.clear();
100  haltChildren();
101  return NodeStatus::SUCCESS;
102  }
103  } break;
104 
105  case NodeStatus::FAILURE:
106  {
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 - success_threshold_)
116  || (failure_childred_num == failure_threshold_))
117  {
118  skip_list_.clear();
119  haltChildren();
120  return NodeStatus::FAILURE;
121  }
122  } break;
123 
124  case NodeStatus::RUNNING:
125  {
126  // do nothing
127  } break;
128 
129  default:
130  {
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_;
148 }
149 
151 {
152  return failure_threshold_;
153 }
154 
155 void ParallelNode::setThresholdM(unsigned int threshold_M)
156 {
157  success_threshold_ = threshold_M;
158 }
159 
160 void ParallelNode::setThresholdFM(unsigned int threshold_M)
161 {
162  failure_threshold_ = threshold_M;
163 }
164 
165 }
unsigned int thresholdM()
const std::string & name() const
Name of the instance, not the type.
Definition: tree_node.cpp:73
std::vector< TreeNode * > children_nodes_
Definition: control_node.h:25
const NodeConfiguration & config() const
Definition: tree_node.cpp:99
virtual void halt() override
void setThresholdFM(unsigned int threshold_M)
static constexpr const char * THRESHOLD_SUCCESS
Definition: parallel_node.h:54
unsigned int success_threshold_
Definition: parallel_node.h:48
static constexpr const char * THRESHOLD_FAILURE
Definition: parallel_node.h:55
std::set< int > skip_list_
Definition: parallel_node.h:51
bool read_parameter_from_ports_
Definition: parallel_node.h:53
void setThresholdM(unsigned int threshold_M)
virtual void halt() override
unsigned int thresholdFM()
Result getInput(const std::string &key, T &destination) const
Definition: tree_node.h:192
Abstract base class for Behavior Tree Nodes.
Definition: tree_node.h:53
unsigned int failure_threshold_
Definition: parallel_node.h:49
void setRegistrationID(StringView ID)
Definition: tree_node.h:163
ParallelNode(const std::string &name, unsigned success_threshold, unsigned failure_threshold=1)
NodeStatus status() const
Definition: tree_node.cpp:56
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:33


behaviotree_cpp_v3
Author(s): Michele Colledanchise, Davide Faconti
autogenerated on Tue May 4 2021 02:56:25