Abstract base class for Behavior Tree Nodes. More...
#include <tree_node.h>
Public Types | |
typedef std::shared_ptr< TreeNode > | Ptr |
using | StatusChangeCallback = StatusChangeSignal::CallableFunction |
using | StatusChangeSignal = Signal< TimePoint, const TreeNode &, NodeStatus, NodeStatus > |
using | StatusChangeSubscriber = StatusChangeSignal::Subscriber |
Public Member Functions | |
const NodeConfiguration & | config () const |
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 |
virtual void | halt ()=0 |
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 | setStatus (NodeStatus new_status) |
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... | |
virtual NodeType | type () const =0 |
uint16_t | UID () const |
BT::NodeStatus | waitValidStatus () |
virtual | ~TreeNode ()=default |
Static Public Member Functions | |
static Optional< StringView > | getRemappedKey (StringView port_name, StringView remapping_value) |
static bool | isBlackboardPointer (StringView str) |
static StringView | stripBlackboardPointer (StringView str) |
Protected Member Functions | |
void | modifyPortsRemapping (const PortsRemapping &new_remapping) |
void | setRegistrationID (StringView ID) |
virtual BT::NodeStatus | tick ()=0 |
Method to be implemented by the user. More... | |
Private Attributes | |
NodeConfiguration | config_ |
const std::string | name_ |
std::string | registration_ID_ |
StatusChangeSignal | state_change_signal_ |
std::condition_variable | state_condition_variable_ |
std::mutex | state_mutex_ |
NodeStatus | status_ |
const uint16_t | uid_ |
Friends | |
class | BehaviorTreeFactory |
Abstract base class for Behavior Tree Nodes.
Definition at line 53 of file tree_node.h.
typedef std::shared_ptr<TreeNode> BT::TreeNode::Ptr |
Definition at line 56 of file tree_node.h.
Definition at line 96 of file tree_node.h.
using BT::TreeNode::StatusChangeSignal = Signal<TimePoint, const TreeNode&, NodeStatus, NodeStatus> |
Definition at line 94 of file tree_node.h.
Definition at line 95 of file tree_node.h.
BT::TreeNode::TreeNode | ( | std::string | name, |
NodeConfiguration | config | ||
) |
TreeNode main constructor.
name | name of the instance, not the type. |
config | information about input/output ports. See NodeConfiguration |
Note: If your custom node has ports, the derived class must implement:
static PortsList providedPorts();
Definition at line 25 of file tree_node.cpp.
|
virtualdefault |
const NodeConfiguration & BT::TreeNode::config | ( | ) | const |
Configuration passed at construction time. Can never change after the creation of the TreeNode instance.
Definition at line 99 of file tree_node.cpp.
|
virtual |
The method that should be used to invoke tick() and setStatus();.
Reimplemented in BT::CoroActionNode, BT::AsyncActionNode, BT::SyncActionNode, and BT::DecoratorNode.
Definition at line 33 of file tree_node.cpp.
|
inline |
Read an input port, which, in practice, is an entry in the blackboard. If the blackboard contains a std::string and T is not a string, convertFromString<T>() is used automatically to parse the text.
key | the identifier (before remapping) of the port. |
Definition at line 185 of file tree_node.h.
|
inline |
Same as bool getInput(const std::string& key, T& destination) but using optional.
Definition at line 133 of file tree_node.h.
|
static |
Definition at line 134 of file tree_node.cpp.
|
pure virtual |
The method used to interrupt the execution of a RUNNING node. Only Async nodes that may return RUNNING should implement it.
Implemented in BT::CoroActionNode, FollowPath, MyAsyncAction, MoveBaseAction, BT::SyncActionNode, BT::RepeatNode, BT::RetryNode, BT::AsyncActionTest, BT::ControlNode, BT::SequenceStarNode, BT::SequenceNode, BT::FallbackNode, BT::ParallelNode, BT::ConditionNode, BT::DecoratorNode, and SimpleCoroAction.
|
static |
Check a string and return true if it matches either one of these two patterns: {...} or ${...}
Definition at line 104 of file tree_node.cpp.
bool BT::TreeNode::isHalted | ( | ) | const |
Definition at line 78 of file tree_node.cpp.
|
protected |
Definition at line 147 of file tree_node.cpp.
const std::string & BT::TreeNode::name | ( | ) | const |
Name of the instance, not the type.
Definition at line 73 of file tree_node.cpp.
const std::string & BT::TreeNode::registrationName | ( | ) | const |
registrationName is the ID used by BehaviorTreeFactory to create an instance.
Definition at line 94 of file tree_node.cpp.
|
inline |
Definition at line 236 of file tree_node.h.
|
inlineprotected |
Definition at line 158 of file tree_node.h.
void BT::TreeNode::setStatus | ( | NodeStatus | new_status | ) |
Definition at line 40 of file tree_node.cpp.
NodeStatus BT::TreeNode::status | ( | ) | const |
Definition at line 56 of file tree_node.cpp.
|
static |
Definition at line 119 of file tree_node.cpp.
TreeNode::StatusChangeSubscriber BT::TreeNode::subscribeToStatusChange | ( | TreeNode::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.
callback | The callback to be execute when status change. |
Definition at line 84 of file tree_node.cpp.
|
protectedpure virtual |
Method to be implemented by the user.
Implemented in FollowPath, ComputePathToPose, BackUpAndSpin, BT::SimpleActionNode, IsStuck, PrintTarget, BT::SimpleConditionNode, MoveBaseAction, BT::RetryNode, BT::SimpleDecoratorNode, BB_TypedTestNode, BT::RepeatNode, ThinkWhatToSay, BT::BlackboardPreconditionNode< T >, Action_B, DummyNodes::SaySomething, BT::ParallelNode, BT::SequenceStarNode, BT::SetBlackboard, BT::SequenceNode, BT::FallbackNode, CalculateGoal, BT::ReactiveFallback, BT::TimeoutNode, BT::ReactiveSequence, SimpleCoroAction, DummyNodes::ApproachObject, BT::AsyncActionTest, BT::InverterNode, BT::AlwaysFailureNode, BT::AlwaysSuccessNode, BT::ForceFailureNode, BT::ForceSuccessNode, BB_TestNode, Action_A, MyAsyncAction, BT::DecoratorSubtreeNode, BT::ConditionTestNode, and BT::SyncActionTest.
|
pure virtual |
Implemented in BT::ControlNode, BT::ActionNodeBase, BT::ConditionNode, BT::DecoratorNode, and BT::DecoratorSubtreeNode.
uint16_t BT::TreeNode::UID | ( | ) | const |
Definition at line 89 of file tree_node.cpp.
NodeStatus BT::TreeNode::waitValidStatus | ( | ) |
Blocking function that will sleep until the setStatus() is called with either RUNNING, FAILURE or SUCCESS.
Definition at line 62 of file tree_node.cpp.
|
friend |
Definition at line 155 of file tree_node.h.
|
private |
Definition at line 178 of file tree_node.h.
|
private |
Definition at line 166 of file tree_node.h.
|
private |
Definition at line 180 of file tree_node.h.
|
private |
Definition at line 174 of file tree_node.h.
|
private |
Definition at line 170 of file tree_node.h.
|
mutableprivate |
Definition at line 172 of file tree_node.h.
|
private |
Definition at line 168 of file tree_node.h.
|
private |
Definition at line 176 of file tree_node.h.