BehaviorTree
Core Library to create and execute Behavior Trees
Loading...
Searching...
No Matches
parallel_all_node.h
1/* Copyright (C) 2023-2025 Davide Faconti - All Rights Reserved
2*
3* Permission is hereby granted, free of charge, to any person obtaining a copy of this software and associated documentation files (the "Software"),
4* to deal in the Software without restriction, including without limitation the rights to use, copy, modify, merge, publish, distribute, sublicense,
5* 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:
6* The above copyright notice and this permission notice shall be included in all copies or substantial portions of the Software.
7*
8* THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY,
9* 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,
10* 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.
11*/
12
13#pragma once
14
15#include "behaviortree_cpp/control_node.h"
16
17#include <set>
18
19namespace BT
20{
21/**
22 * @brief The ParallelAllNode execute all its children
23 * __concurrently__, but not in separate threads!
24 *
25 * It differs in the way ParallelNode works because the latter may stop
26 * and halt other children if a certain number of SUCCESS/FAILURES is reached,
27 * whilst this one will always complete the execution of ALL its children.
28 *
29 * Note that threshold indexes work as in Python:
30 * https://www.i2tutorials.com/what-are-negative-indexes-and-why-are-they-used/
31 *
32 * Therefore -1 is equivalent to the number of children.
33 */
34class ParallelAllNode : public ControlNode
35{
36public:
37 ParallelAllNode(const std::string& name, const NodeConfig& config);
38
39 static PortsList providedPorts()
40 {
41 return { InputPort<int>("max_failures", 1,
42 "If the number of children returning FAILURE exceeds this "
43 "value, "
44 "ParallelAll returns FAILURE") };
45 }
46
47 ~ParallelAllNode() override = default;
48
49 ParallelAllNode(const ParallelAllNode&) = delete;
50 ParallelAllNode& operator=(const ParallelAllNode&) = delete;
51 ParallelAllNode(ParallelAllNode&&) = delete;
52 ParallelAllNode& operator=(ParallelAllNode&&) = delete;
53
54 virtual void halt() override;
55
56 size_t failureThreshold() const;
57 void setFailureThreshold(int threshold);
58
59private:
60 size_t failure_threshold_;
61
62 std::set<size_t> completed_list_;
63 size_t failure_count_ = 0;
64
65 virtual BT::NodeStatus tick() override;
66};
67
68} // namespace BT
The ControlNode is the base class for nodes that can have multiple children.
Definition: control_node.h:32
The ParallelAllNode execute all its children concurrently, but not in separate threads!
Definition: parallel_all_node.h:35
virtual void halt() override
Definition: action_node.h:24
NodeStatus
Definition: basic_types.h:34
Definition: tree_node.h:105