The ParallelNode execute all its children concurrently, but not in separate threads! More...
#include <parallel_node.h>
Public Member Functions | |
size_t | failureThreshold () const |
virtual void | halt () override |
ParallelNode (const std::string &name, int success_threshold, int failure_threshold=1) | |
ParallelNode (const std::string &name, const NodeConfiguration &config) | |
void | setFailureThreshold (int threshold_M) |
void | setSuccessThreshold (int threshold_M) |
size_t | successThreshold () const |
~ParallelNode () override=default | |
![]() | |
void | addChild (TreeNode *child) |
The method used to add nodes to the children vector. More... | |
const TreeNode * | child (size_t index) const |
const std::vector< TreeNode * > & | children () const |
size_t | childrenCount () const |
ControlNode (const std::string &name, const NodeConfiguration &config) | |
void | haltChild (size_t i) |
void | haltChildren () |
same as resetChildren() More... | |
void | haltChildren (size_t first) |
void | resetChildren () |
virtual NodeType | type () const override final |
virtual | ~ControlNode () override=default |
![]() | |
const NodeConfiguration & | config () const |
void | emitStateChanged () |
virtual BT::NodeStatus | executeTick () |
The method that should be used to invoke tick() and setStatus();. More... | |
template<typename T > | |
Result | getInput (const std::string &key, T &destination) const |
template<typename T > | |
Optional< T > | getInput (const std::string &key) const |
StringView | getRawPortValue (const std::string &key) const |
bool | isHalted () const |
const std::string & | name () const |
Name of the instance, not the type. More... | |
const std::string & | registrationName () const |
registrationName is the ID used by BehaviorTreeFactory to create an instance. More... | |
template<typename T > | |
Result | setOutput (const std::string &key, const T &value) |
void | setPostTickOverrideFunction (PostTickOverrideCallback callback) |
void | setPreTickOverrideFunction (PreTickOverrideCallback callback) |
NodeStatus | status () const |
StatusChangeSubscriber | subscribeToStatusChange (StatusChangeCallback callback) |
subscribeToStatusChange is used to attach a callback to a status change. When StatusChangeSubscriber goes out of scope (it is a shared_ptr) the callback is unsubscribed automatically. More... | |
TreeNode (std::string name, NodeConfiguration config) | |
TreeNode main constructor. More... | |
uint16_t | UID () const |
BT::NodeStatus | waitValidStatus () |
virtual | ~TreeNode ()=default |
Static Public Member Functions | |
static PortsList | providedPorts () |
![]() | |
static Optional< StringView > | getRemappedKey (StringView port_name, StringView remapping_value) |
static bool | isBlackboardPointer (StringView str) |
static StringView | stripBlackboardPointer (StringView str) |
Private Member Functions | |
virtual BT::NodeStatus | tick () override |
Method to be implemented by the user. More... | |
Private Attributes | |
int | failure_threshold_ |
bool | read_parameter_from_ports_ |
std::set< int > | skip_list_ |
int | success_threshold_ |
Static Private Attributes | |
static constexpr const char * | THRESHOLD_FAILURE = "failure_threshold" |
static constexpr const char * | THRESHOLD_SUCCESS = "success_threshold" |
Additional Inherited Members | |
![]() | |
using | PostTickOverrideCallback = std::function< Optional< NodeStatus >(TreeNode &, NodeStatus, NodeStatus)> |
using | PreTickOverrideCallback = std::function< Optional< NodeStatus >(TreeNode &, NodeStatus)> |
typedef std::shared_ptr< TreeNode > | Ptr |
using | StatusChangeCallback = StatusChangeSignal::CallableFunction |
using | StatusChangeSignal = Signal< TimePoint, const TreeNode &, NodeStatus, NodeStatus > |
using | StatusChangeSubscriber = StatusChangeSignal::Subscriber |
![]() | |
void | modifyPortsRemapping (const PortsRemapping &new_remapping) |
void | resetStatus () |
Equivalent to setStatus(NodeStatus::IDLE) More... | |
void | setRegistrationID (StringView ID) |
void | setStatus (NodeStatus new_status) |
void | setWakeUpInstance (std::shared_ptr< WakeUpSignal > instance) |
![]() | |
std::vector< TreeNode * > | children_nodes_ |
The ParallelNode execute all its children concurrently, but not in separate threads!
Even if this may look similar to ReactiveSequence, this Control Node is the only one that can have multiple children RUNNING at the same time.
The Node is completed either when the THRESHOLD_SUCCESS or THRESHOLD_FAILURE number is reached (both configured using ports).
If any of the threaholds is reached, and other children are still running, they will be halted.
Note that threshold indexes work as in Python: https://www.i2tutorials.com/what-are-negative-indexes-and-why-are-they-used/
Therefore -1 is equivalent to the number of children.
Definition at line 40 of file parallel_node.h.
BT::ParallelNode::ParallelNode | ( | const std::string & | name, |
int | success_threshold, | ||
int | failure_threshold = 1 |
||
) |
Definition at line 24 of file parallel_node.cpp.
BT::ParallelNode::ParallelNode | ( | const std::string & | name, |
const NodeConfiguration & | config | ||
) |
Definition at line 34 of file parallel_node.cpp.
|
overridedefault |
size_t BT::ParallelNode::failureThreshold | ( | ) | const |
Definition at line 152 of file parallel_node.cpp.
|
overridevirtual |
The method used to interrupt the execution of a RUNNING node. Only Async nodes that may return RUNNING should implement it.
Reimplemented from BT::ControlNode.
Definition at line 139 of file parallel_node.cpp.
|
inlinestatic |
Definition at line 47 of file parallel_node.h.
void BT::ParallelNode::setFailureThreshold | ( | int | threshold_M | ) |
Definition at line 164 of file parallel_node.cpp.
void BT::ParallelNode::setSuccessThreshold | ( | int | threshold_M | ) |
Definition at line 159 of file parallel_node.cpp.
size_t BT::ParallelNode::successThreshold | ( | ) | const |
Definition at line 145 of file parallel_node.cpp.
|
overrideprivatevirtual |
Method to be implemented by the user.
Implements BT::TreeNode.
Definition at line 41 of file parallel_node.cpp.
|
private |
Definition at line 67 of file parallel_node.h.
|
private |
Definition at line 71 of file parallel_node.h.
|
private |
Definition at line 69 of file parallel_node.h.
|
private |
Definition at line 66 of file parallel_node.h.
|
staticprivate |
Definition at line 73 of file parallel_node.h.
|
staticprivate |
Definition at line 72 of file parallel_node.h.