Classes | Public Types | Public Member Functions | Static Public Member Functions | Protected Types | Protected Member Functions | Private Member Functions | Private Attributes | Friends | List of all members
BT::TreeNode Class Referenceabstract

Abstract base class for Behavior Tree Nodes. More...

#include <tree_node.h>

Inheritance diagram for BT::TreeNode:
Inheritance graph
[legend]

Classes

struct  PImpl
 

Public Types

using PostTickCallback = std::function< NodeStatus(TreeNode &, NodeStatus)>
 
using PreTickCallback = std::function< NodeStatus(TreeNode &)>
 
typedef std::shared_ptr< TreeNodePtr
 
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 NodeConfigconfig () 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< TimestampgetInputStamped (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...
 
TreeNodeoperator= (const TreeNode &other)=delete
 
TreeNodeoperator= (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< StringViewgetRemappedKey (StringView port_name, StringView remapped_port)
 
template<class DerivedT , typename... ExtraArgs>
static std::unique_ptr< TreeNodeInstantiate (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

NodeConfigconfig ()
 
void modifyPortsRemapping (const PortsRemapping &new_remapping)
 
template<typename T >
parseString (const std::string &str) const
 
PostScriptspostConditionsScripts ()
 
PreScriptspreConditionsScripts ()
 
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< NodeStatuscheckPreConditions ()
 
virtual void halt ()=0
 

Private Attributes

std::unique_ptr< PImpl_p
 

Friends

class BehaviorTreeFactory
 
class ControlNode
 
class DecoratorNode
 
class Tree
 

Detailed Description

Abstract base class for Behavior Tree Nodes.

Definition at line 118 of file tree_node.h.

Member Typedef Documentation

◆ PostScripts

using BT::TreeNode::PostScripts = std::array<ScriptFunction, size_t(PostCond::COUNT_)>
protected

Definition at line 395 of file tree_node.h.

◆ PostTickCallback

Definition at line 166 of file tree_node.h.

◆ PreScripts

using BT::TreeNode::PreScripts = std::array<ScriptFunction, size_t(PreCond::COUNT_)>
protected

Definition at line 394 of file tree_node.h.

◆ PreTickCallback

Definition at line 165 of file tree_node.h.

◆ Ptr

typedef std::shared_ptr<TreeNode> BT::TreeNode::Ptr

Definition at line 121 of file tree_node.h.

◆ StatusChangeCallback

Definition at line 163 of file tree_node.h.

◆ StatusChangeSignal

Definition at line 161 of file tree_node.h.

◆ StatusChangeSubscriber

Definition at line 162 of file tree_node.h.

◆ TickMonitorCallback

using BT::TreeNode::TickMonitorCallback = std::function<void(TreeNode&, NodeStatus, std::chrono::microseconds)>

Definition at line 168 of file tree_node.h.

Constructor & Destructor Documentation

◆ TreeNode() [1/3]

BT::TreeNode::TreeNode ( std::string  name,
NodeConfig  config 
)

TreeNode main constructor.

Parameters
namename of the instance, not the type.
configinformation 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.

◆ TreeNode() [2/3]

BT::TreeNode::TreeNode ( const TreeNode other)
delete

◆ TreeNode() [3/3]

BT::TreeNode::TreeNode ( TreeNode &&  other)
noexcept

Definition at line 57 of file tree_node.cpp.

◆ ~TreeNode()

BT::TreeNode::~TreeNode ( )
virtual

Definition at line 68 of file tree_node.cpp.

Member Function Documentation

◆ checkPostConditions()

void BT::TreeNode::checkPostConditions ( NodeStatus  status)
private

Definition at line 240 of file tree_node.cpp.

◆ checkPreConditions()

Expected< NodeStatus > BT::TreeNode::checkPreConditions ( )
private

Definition at line 187 of file tree_node.cpp.

◆ config() [1/2]

NodeConfig& BT::TreeNode::config ( )
protected

◆ config() [2/2]

NodeConfig & BT::TreeNode::config ( ) const

Configuration passed at construction time. Can never change after the creation of the TreeNode instance.

Definition at line 345 of file tree_node.cpp.

◆ emitWakeUpSignal()

void BT::TreeNode::emitWakeUpSignal ( )

Notify that the tree should be ticked again()

Definition at line 420 of file tree_node.cpp.

◆ executeTick()

NodeStatus BT::TreeNode::executeTick ( )
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.

◆ fullPath()

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 335 of file tree_node.cpp.

◆ getInput() [1/2]

template<typename T >
Expected<T> BT::TreeNode::getInput ( const std::string &  key) const
inline

Same as bool getInput(const std::string& key, T& destination) but using optional.

Parameters
keythe name of the port.

Definition at line 257 of file tree_node.h.

◆ getInput() [2/2]

template<typename T >
Result BT::TreeNode::getInput ( const std::string &  key,
T &  destination 
) const
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.

Parameters
keythe name of the port.
destinationreference to the object where the value should be stored
Returns
false if an error occurs.

Definition at line 547 of file tree_node.h.

◆ getInputStamped() [1/2]

template<typename T >
Expected<StampedValue<T> > BT::TreeNode::getInputStamped ( const std::string &  key) const
inline

Same as bool getInputStamped(const std::string& key, T& destination) but return StampedValue<T>

Parameters
keythe name of the port.

Definition at line 270 of file tree_node.h.

◆ getInputStamped() [2/2]

template<typename T >
Expected< Timestamp > BT::TreeNode::getInputStamped ( const std::string &  key,
T &  destination 
) const
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.

Parameters
keythe name of the port.
destinationreference to the object where the value should be stored

Definition at line 438 of file tree_node.h.

◆ getLockedPortContent()

AnyPtrLocked BT::TreeNode::getLockedPortContent ( const std::string &  key)

getLockedPortContent should be used when:

  • your port contains an object with reference semantic (usually a smart pointer)
  • you want to modify the object we are pointing to.
  • you are concerned about thread-safety.

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.

Parameters
keythe identifier of the port.
Returns
empty AnyPtrLocked if the blackboard entry doesn't exist or the content of the port was a static string.

Definition at line 496 of file tree_node.cpp.

◆ getRawPortValue()

StringView BT::TreeNode::getRawPortValue ( const std::string &  key) const

Definition at line 355 of file tree_node.cpp.

◆ getRemappedKey()

Expected< StringView > BT::TreeNode::getRemappedKey ( StringView  port_name,
StringView  remapped_port 
)
static

Definition at line 405 of file tree_node.cpp.

◆ halt()

virtual void BT::TreeNode::halt ( )
privatepure virtual

◆ haltNode()

void BT::TreeNode::haltNode ( )

Definition at line 142 of file tree_node.cpp.

◆ Instantiate()

template<class DerivedT , typename... ExtraArgs>
static std::unique_ptr<TreeNode> BT::TreeNode::Instantiate ( const std::string &  name,
const NodeConfig config,
ExtraArgs...  args 
)
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.

◆ isBlackboardPointer()

bool BT::TreeNode::isBlackboardPointer ( StringView  str,
StringView stripped_pointer = nullptr 
)
static

Check a string and return true if it matches the pattern: {...}.

Definition at line 369 of file tree_node.cpp.

◆ isHalted()

bool BT::TreeNode::isHalted ( ) const

Definition at line 301 of file tree_node.cpp.

◆ modifyPortsRemapping()

void BT::TreeNode::modifyPortsRemapping ( const PortsRemapping new_remapping)
protected

Definition at line 443 of file tree_node.cpp.

◆ name()

const std::string & BT::TreeNode::name ( ) const

Name of the instance, not the type.

Definition at line 296 of file tree_node.cpp.

◆ operator=() [1/2]

TreeNode& BT::TreeNode::operator= ( const TreeNode other)
delete

◆ operator=() [2/2]

TreeNode & BT::TreeNode::operator= ( TreeNode &&  other)
noexcept

Definition at line 62 of file tree_node.cpp.

◆ parseString()

template<typename T >
T BT::TreeNode::parseString ( const std::string &  str) const
protected

Definition at line 418 of file tree_node.h.

◆ postConditionsScripts()

TreeNode::PostScripts & BT::TreeNode::postConditionsScripts ( )
protected

Definition at line 182 of file tree_node.cpp.

◆ preConditionsScripts()

TreeNode::PreScripts & BT::TreeNode::preConditionsScripts ( )
protected

Definition at line 177 of file tree_node.cpp.

◆ registrationName()

const std::string & BT::TreeNode::registrationName ( ) const

registrationName is the ID used by BehaviorTreeFactory to create an instance.

Definition at line 340 of file tree_node.cpp.

◆ requiresWakeUp()

bool BT::TreeNode::requiresWakeUp ( ) const

Definition at line 428 of file tree_node.cpp.

◆ resetStatus()

void BT::TreeNode::resetStatus ( )
protected

Set the status to IDLE.

Definition at line 262 of file tree_node.cpp.

◆ setOutput()

template<typename T >
Result BT::TreeNode::setOutput ( const std::string &  key,
const T &  value 
)
inline

setOutput modifies the content of an Output port

Parameters
keythe name of the port.
valuenew value
Returns
valid Result, if succesful.

Definition at line 558 of file tree_node.h.

◆ setPostTickFunction()

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 318 of file tree_node.cpp.

◆ setPreTickFunction()

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 312 of file tree_node.cpp.

◆ setRegistrationID()

void BT::TreeNode::setRegistrationID ( StringView  ID)
protected

Definition at line 433 of file tree_node.cpp.

◆ setStatus()

void BT::TreeNode::setStatus ( NodeStatus  new_status)
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 154 of file tree_node.cpp.

◆ setTickMonitorCallback()

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 324 of file tree_node.cpp.

◆ setWakeUpInstance()

void BT::TreeNode::setWakeUpInstance ( std::shared_ptr< WakeUpSignal instance)
protected

Definition at line 438 of file tree_node.cpp.

◆ status()

NodeStatus BT::TreeNode::status ( ) const

Definition at line 279 of file tree_node.cpp.

◆ stripBlackboardPointer()

StringView BT::TreeNode::stripBlackboardPointer ( StringView  str)
static

Definition at line 395 of file tree_node.cpp.

◆ subscribeToStatusChange()

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.

Parameters
callbackThe callback to be execute when status change.
Returns
the subscriber handle.

Definition at line 307 of file tree_node.cpp.

◆ tick()

virtual BT::NodeStatus BT::TreeNode::tick ( )
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.

◆ type()

virtual NodeType BT::TreeNode::type ( ) const
pure virtual

◆ UID()

uint16_t BT::TreeNode::UID ( ) const

The unique identifier of this instance of treeNode. It is assigneld by the factory

Definition at line 330 of file tree_node.cpp.

◆ waitValidStatus()

NodeStatus BT::TreeNode::waitValidStatus ( )

Blocking function that will sleep until the setStatus() is called with either RUNNING, FAILURE or SUCCESS.

Definition at line 285 of file tree_node.cpp.

Friends And Related Function Documentation

◆ BehaviorTreeFactory

friend class BehaviorTreeFactory
friend

Definition at line 367 of file tree_node.h.

◆ ControlNode

friend class ControlNode
friend

Definition at line 369 of file tree_node.h.

◆ DecoratorNode

friend class DecoratorNode
friend

Definition at line 368 of file tree_node.h.

◆ Tree

friend class Tree
friend

Definition at line 370 of file tree_node.h.

Member Data Documentation

◆ _p

std::unique_ptr<PImpl> BT::TreeNode::_p
private

Definition at line 404 of file tree_node.h.


The documentation for this class was generated from the following files:


behaviortree_cpp_v4
Author(s): Davide Faconti
autogenerated on Fri Jun 28 2024 02:20:09