Abstract base class for Behavior Tree Nodes. More...
#include <tree_node.h>
Classes | |
struct | PImpl |
Public Types | |
using | PostTickCallback = std::function< NodeStatus(TreeNode &, NodeStatus)> |
using | PreTickCallback = std::function< NodeStatus(TreeNode &)> |
typedef std::shared_ptr< TreeNode > | Ptr |
using | StatusChangeCallback = StatusChangeSignal::CallableFunction |
using | StatusChangeSignal = Signal< TimePoint, const TreeNode &, NodeStatus, NodeStatus > |
using | StatusChangeSubscriber = StatusChangeSignal::Subscriber |
using | TickMonitorCallback = std::function< void(TreeNode &, NodeStatus, std::chrono::microseconds)> |
Public Member Functions | |
const NodeConfig & | config () const |
void | emitWakeUpSignal () |
Notify that the tree should be ticked again() More... | |
virtual BT::NodeStatus | executeTick () |
The method that should be used to invoke tick() and setStatus();. More... | |
const std::string & | fullPath () const |
template<typename T > | |
Expected< T > | getInput (const std::string &key) const |
template<typename T > | |
Result | getInput (const std::string &key, T &destination) const |
template<typename T > | |
Expected< StampedValue< T > > | getInputStamped (const std::string &key) const |
template<typename T > | |
Expected< Timestamp > | getInputStamped (const std::string &key, T &destination) const |
getInputStamped is similar to getInput(dey, destination), but it returne also the Timestamp object, that can be used to check if a value was updated and when. More... | |
AnyPtrLocked | getLockedPortContent (const std::string &key) |
getLockedPortContent should be used when: More... | |
StringView | getRawPortValue (const std::string &key) const |
void | haltNode () |
bool | isHalted () const |
const std::string & | name () const |
Name of the instance, not the type. More... | |
TreeNode & | operator= (const TreeNode &other)=delete |
TreeNode & | operator= (TreeNode &&other) noexcept |
const std::string & | registrationName () const |
registrationName is the ID used by BehaviorTreeFactory to create an instance. More... | |
bool | requiresWakeUp () const |
template<typename T > | |
Result | setOutput (const std::string &key, const T &value) |
setOutput modifies the content of an Output port More... | |
void | setPostTickFunction (PostTickCallback callback) |
void | setPreTickFunction (PreTickCallback callback) |
void | setTickMonitorCallback (TickMonitorCallback 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 (const TreeNode &other)=delete | |
TreeNode (std::string name, NodeConfig config) | |
TreeNode main constructor. More... | |
TreeNode (TreeNode &&other) noexcept | |
virtual NodeType | type () const =0 |
uint16_t | UID () const |
BT::NodeStatus | waitValidStatus () |
virtual | ~TreeNode () |
Static Public Member Functions | |
static Expected< StringView > | getRemappedKey (StringView port_name, StringView remapped_port) |
template<class DerivedT , typename... ExtraArgs> | |
static std::unique_ptr< TreeNode > | Instantiate (const std::string &name, const NodeConfig &config, ExtraArgs... args) |
static bool | isBlackboardPointer (StringView str, StringView *stripped_pointer=nullptr) |
Check a string and return true if it matches the pattern: {...}. More... | |
static StringView | stripBlackboardPointer (StringView str) |
Protected Types | |
using | PostScripts = std::array< ScriptFunction, size_t(PostCond::COUNT_)> |
using | PreScripts = std::array< ScriptFunction, size_t(PreCond::COUNT_)> |
Protected Member Functions | |
NodeConfig & | config () |
void | modifyPortsRemapping (const PortsRemapping &new_remapping) |
template<typename T > | |
T | parseString (const std::string &str) const |
PostScripts & | postConditionsScripts () |
PreScripts & | preConditionsScripts () |
void | resetStatus () |
Set the status to IDLE. More... | |
void | setRegistrationID (StringView ID) |
void | setStatus (NodeStatus new_status) |
setStatus changes the status of the node. it will throw if you try to change the status to IDLE, because your parent node should do that, not the user! More... | |
void | setWakeUpInstance (std::shared_ptr< WakeUpSignal > instance) |
virtual BT::NodeStatus | tick ()=0 |
Method to be implemented by the user. More... | |
Private Member Functions | |
void | checkPostConditions (NodeStatus status) |
Expected< NodeStatus > | checkPreConditions () |
virtual void | halt ()=0 |
Private Attributes | |
std::unique_ptr< PImpl > | _p |
Friends | |
class | BehaviorTreeFactory |
class | ControlNode |
class | DecoratorNode |
class | Tree |
Abstract base class for Behavior Tree Nodes.
Definition at line 118 of file tree_node.h.
|
protected |
Definition at line 395 of file tree_node.h.
using BT::TreeNode::PostTickCallback = std::function<NodeStatus(TreeNode&, NodeStatus)> |
Definition at line 166 of file tree_node.h.
|
protected |
Definition at line 394 of file tree_node.h.
using BT::TreeNode::PreTickCallback = std::function<NodeStatus(TreeNode&)> |
Definition at line 165 of file tree_node.h.
typedef std::shared_ptr<TreeNode> BT::TreeNode::Ptr |
Definition at line 121 of file tree_node.h.
Definition at line 163 of file tree_node.h.
using BT::TreeNode::StatusChangeSignal = Signal<TimePoint, const TreeNode&, NodeStatus, NodeStatus> |
Definition at line 161 of file tree_node.h.
Definition at line 162 of file tree_node.h.
using BT::TreeNode::TickMonitorCallback = std::function<void(TreeNode&, NodeStatus, std::chrono::microseconds)> |
Definition at line 168 of file tree_node.h.
BT::TreeNode::TreeNode | ( | std::string | name, |
NodeConfig | config | ||
) |
TreeNode main constructor.
name | name of the instance, not the type. |
config | information about input/output ports. See NodeConfig |
Note: If your custom node has ports, the derived class must implement:
static PortsList providedPorts();
Definition at line 53 of file tree_node.cpp.
|
delete |
|
noexcept |
Definition at line 57 of file tree_node.cpp.
|
virtual |
Definition at line 68 of file tree_node.cpp.
|
private |
Definition at line 246 of file tree_node.cpp.
|
private |
Definition at line 193 of file tree_node.cpp.
|
protected |
NodeConfig & BT::TreeNode::config | ( | ) | const |
Configuration passed at construction time. Can never change after the creation of the TreeNode instance.
Definition at line 351 of file tree_node.cpp.
void BT::TreeNode::emitWakeUpSignal | ( | ) |
Notify that the tree should be ticked again()
Definition at line 426 of file tree_node.cpp.
|
virtual |
The method that should be used to invoke tick() and setStatus();.
Reimplemented in BT::CoroActionNode, BT::ThreadedAction, BT::SyncActionNode, and BT::DecoratorNode.
Definition at line 71 of file tree_node.cpp.
const std::string & BT::TreeNode::fullPath | ( | ) | const |
Human readable identifier, that includes the hierarchy of Subtrees See tutorial 10 as an example.
Definition at line 341 of file tree_node.cpp.
|
inline |
Same as bool getInput(const std::string& key, T& destination) but using optional.
key | the name of the port. |
Definition at line 257 of file tree_node.h.
|
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 name of the port. |
destination | reference to the object where the value should be stored |
Definition at line 547 of file tree_node.h.
|
inline |
Same as bool getInputStamped(const std::string& key, T& destination) but return StampedValue<T>
key | the name of the port. |
Definition at line 270 of file tree_node.h.
|
inline |
getInputStamped is similar to getInput(dey, destination), but it returne also the Timestamp object, that can be used to check if a value was updated and when.
key | the name of the port. |
destination | reference to the object where the value should be stored |
Definition at line 438 of file tree_node.h.
AnyPtrLocked BT::TreeNode::getLockedPortContent | ( | const std::string & | key | ) |
getLockedPortContent should be used when:
For example, if your port has type std::shared_ptr<Foo>, the code below is NOT thread safe:
auto foo_ptr = getInput<std::shared_ptr<Foo>>("port_name"); // modifying the content of foo_ptr is NOT thread-safe
What you must do, instead, to guaranty thread-safety, is:
if(auto any_ref = getLockedPortContent("port_name")) { Any* any = any_ref.get(); auto foo_ptr = any->cast<std::shared_ptr<Foo>>(); // modifying the content of foo_ptr inside this scope IS thread-safe }
It is important to destroy the object AnyPtrLocked, to release the lock.
NOTE: this method doesn't work, if the port contains a static string, instead of a blackboard pointer.
key | the identifier of the port. |
Definition at line 502 of file tree_node.cpp.
StringView BT::TreeNode::getRawPortValue | ( | const std::string & | key | ) | const |
Definition at line 361 of file tree_node.cpp.
|
static |
Definition at line 411 of file tree_node.cpp.
|
privatepure 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::StatefulActionNode, BT::SyncActionNode, BT::ConditionNode, BT::CoroActionNode, FollowPath, BT::ThreadedAction, BT::TimeoutNode, BT::ParallelNode, BT::RepeatNode, BT::SwitchNode< NUM_CASES >, BT::RetryNode, BT::DelayNode, BT::AsyncActionTest, BT::ParallelAllNode, BT::ReactiveFallback, BT::ReactiveSequence, BT::EntryUpdatedDecorator, BT::ControlNode, BT::IfThenElseNode, BT::SequenceNode, BT::SequenceWithMemory, BT::WhileDoElseNode, BT::FallbackNode, BT::ManualSelectorNode, BT::DecoratorNode, and SimpleCoroAction.
void BT::TreeNode::haltNode | ( | ) |
Definition at line 148 of file tree_node.cpp.
|
inlinestatic |
Used to inject config into a node, even if it doesn't have the proper constructor
Definition at line 347 of file tree_node.h.
|
static |
Check a string and return true if it matches the pattern: {...}.
Definition at line 375 of file tree_node.cpp.
bool BT::TreeNode::isHalted | ( | ) | const |
Definition at line 307 of file tree_node.cpp.
|
protected |
Definition at line 449 of file tree_node.cpp.
const std::string & BT::TreeNode::name | ( | ) | const |
Name of the instance, not the type.
Definition at line 302 of file tree_node.cpp.
Definition at line 62 of file tree_node.cpp.
|
protected |
Definition at line 418 of file tree_node.h.
|
protected |
Definition at line 188 of file tree_node.cpp.
|
protected |
Definition at line 183 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 346 of file tree_node.cpp.
bool BT::TreeNode::requiresWakeUp | ( | ) | const |
Definition at line 434 of file tree_node.cpp.
|
protected |
Set the status to IDLE.
Definition at line 268 of file tree_node.cpp.
|
inline |
setOutput modifies the content of an Output port
key | the name of the port. |
value | new value |
Definition at line 558 of file tree_node.h.
void BT::TreeNode::setPostTickFunction | ( | PostTickCallback | callback | ) |
This method attaches to the TreeNode a callback with signature:
NodeStatus myCallback(TreeNode& node, NodeStatus status)
This callback is executed AFTER the tick() and, if it returns SUCCESS or FAILURE, the value returned by the actual tick() is overriden with this one.
Definition at line 324 of file tree_node.cpp.
void BT::TreeNode::setPreTickFunction | ( | PreTickCallback | callback | ) |
This method attaches to the TreeNode a callback with signature:
NodeStatus callback(TreeNode& node)
This callback is executed BEFORE the tick() and, if it returns SUCCESS or FAILURE, the actual tick() will NOT be executed and this result will be returned instead.
This is useful to inject a "dummy" implementation of the TreeNode at run-time
Definition at line 318 of file tree_node.cpp.
|
protected |
Definition at line 439 of file tree_node.cpp.
|
protected |
setStatus changes the status of the node. it will throw if you try to change the status to IDLE, because your parent node should do that, not the user!
Definition at line 160 of file tree_node.cpp.
void BT::TreeNode::setTickMonitorCallback | ( | TickMonitorCallback | callback | ) |
This method attaches to the TreeNode a callback with signature:
void myCallback(TreeNode& node, NodeStatus status, std::chrono::microseconds duration)
This callback is executed AFTER the tick() and will inform the user about its status and the execution time. Works only if the tick was not substituted by a pre-condition.
Definition at line 330 of file tree_node.cpp.
|
protected |
Definition at line 444 of file tree_node.cpp.
NodeStatus BT::TreeNode::status | ( | ) | const |
Definition at line 285 of file tree_node.cpp.
|
static |
Definition at line 401 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 313 of file tree_node.cpp.
|
protectedpure virtual |
Method to be implemented by the user.
Implemented in BT::StatefulActionNode, BT::SimpleActionNode, NodeWithDefaultNullptr, PrintToConsole, NodeWithDefaultStrings, Assert, NodeWithDefaultPoints, SetAny, GetAny, ActionWithMetadata, ComparisonNode, SampleNode595, DefaultTestAction, NaughtyNav2Node, SimpleOutput, ModifyPose, ActionVectorStringIn, ActionVectorDoubleIn, ReadInConstructor, IllegalPorts, CoroTestNode, IsHealthOk, NodeOutPorts, PrintEnum, NodeInPorts, FollowPath, BT::QueueSize< T >, ComputePathToPose, BackUpAndSpin, IsStuck, UseWaypoint, BT::ParallelNode, Action_B, BT::SubTreeNode, BT::TimeoutNode, PrintTarget, BT::SwitchNode< NUM_CASES >, BT::SimpleDecoratorNode, BT::RetryNode, NodeWithDefaultPoints, BT::PopFromQueue< T >, BT::SimpleConditionNode, BT::ParallelAllNode, BT::DelayNode, BT::RepeatNode, PrintNumber, DummyNodes::SaySomething, BT::LoopNode< T >, ThinkWhatToSay, BT::SetBlackboardNode, PrintNumber, CopyPorts, BT::RunOnceNode, BT::SequenceNode, CalculateGoal, BT::SequenceWithMemory, BT::FallbackNode, BT::IfThenElseNode, BT::ReactiveFallback, BT::ReactiveSequence, BT::EntryUpdatedDecorator, BT::AsyncActionTest, Action_A, BT::ManualSelectorNode, BT::WhileDoElseNode, BT::ScriptCondition, BT::EntryUpdatedAction, DummyNodes::ApproachObject, SimpleCoroAction, BT::PreconditionNode, SayRuntimePort, UpdatePosition, BT::ScriptNode, BT::ConsumeQueue< T >, BT::UnsetBlackboardNode, ActionEnum, BT::InverterNode, BT::KeepRunningUntilFailureNode, BT::AlwaysFailureNode, BT::AlwaysSuccessNode, BT::ForceFailureNode, BT::ForceSuccessNode, SetTask, GenerateWaypoints, ThinkRuntimePort, BT::test::SimpleCondition, FastAction, PushIntoVector, NodeWithPorts, BT::ConditionTestNode, BT::SyncActionTest, PrintVector, BB_TypedTestNode, and BB_TestNode.
|
pure virtual |
Implemented in BT::SubTreeNode, BT::ControlNode, BT::ActionNodeBase, BT::ConditionNode, and BT::DecoratorNode.
uint16_t BT::TreeNode::UID | ( | ) | const |
The unique identifier of this instance of treeNode. It is assigneld by the factory
Definition at line 336 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 291 of file tree_node.cpp.
|
friend |
Definition at line 367 of file tree_node.h.
|
friend |
Definition at line 369 of file tree_node.h.
|
friend |
Definition at line 368 of file tree_node.h.
|
friend |
Definition at line 370 of file tree_node.h.
|
private |
Definition at line 404 of file tree_node.h.