Public Types | Public Member Functions | Static Public Member Functions | Protected 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]

Public Types

using PostTickOverrideCallback = std::function< Optional< NodeStatus >(TreeNode &, NodeStatus, NodeStatus)>
 
using PreTickOverrideCallback = std::function< Optional< NodeStatus >(TreeNode &, NodeStatus)>
 
typedef std::shared_ptr< TreeNodePtr
 
using StatusChangeCallback = StatusChangeSignal::CallableFunction
 
using StatusChangeSignal = Signal< TimePoint, const TreeNode &, NodeStatus, NodeStatus >
 
using StatusChangeSubscriber = StatusChangeSignal::Subscriber
 

Public Member Functions

const NodeConfigurationconfig () 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
 
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 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...
 
virtual NodeType type () const =0
 
uint16_t UID () const
 
BT::NodeStatus waitValidStatus ()
 
virtual ~TreeNode ()=default
 

Static Public Member Functions

static Optional< StringViewgetRemappedKey (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 resetStatus ()
 Equivalent to setStatus(NodeStatus::IDLE) More...
 
void setRegistrationID (StringView ID)
 
void setStatus (NodeStatus new_status)
 
void setWakeUpInstance (std::shared_ptr< WakeUpSignal > instance)
 
virtual BT::NodeStatus tick ()=0
 Method to be implemented by the user. More...
 

Private Attributes

NodeConfiguration config_
 
const std::string name_
 
PostTickOverrideCallback post_condition_callback_
 
PreTickOverrideCallback pre_condition_callback_
 
std::string registration_ID_
 
StatusChangeSignal state_change_signal_
 
std::condition_variable state_condition_variable_
 
std::mutex state_mutex_
 
NodeStatus status_
 
const uint16_t uid_
 
std::shared_ptr< WakeUpSignalwake_up_
 

Friends

class BehaviorTreeFactory
 
class ControlNode
 
class DecoratorNode
 
class Tree
 

Detailed Description

Abstract base class for Behavior Tree Nodes.

Definition at line 55 of file tree_node.h.

Member Typedef Documentation

◆ PostTickOverrideCallback

Definition at line 101 of file tree_node.h.

◆ PreTickOverrideCallback

Definition at line 99 of file tree_node.h.

◆ Ptr

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

Definition at line 58 of file tree_node.h.

◆ StatusChangeCallback

Definition at line 96 of file tree_node.h.

◆ StatusChangeSignal

Definition at line 94 of file tree_node.h.

◆ StatusChangeSubscriber

Definition at line 95 of file tree_node.h.

Constructor & Destructor Documentation

◆ TreeNode()

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

TreeNode main constructor.

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

◆ ~TreeNode()

virtual BT::TreeNode::~TreeNode ( )
virtualdefault

Member Function Documentation

◆ config()

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

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

Definition at line 127 of file tree_node.cpp.

◆ emitStateChanged()

void BT::TreeNode::emitStateChanged ( )

Definition at line 193 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::AsyncActionNode, BT::SyncActionNode, and BT::DecoratorNode.

Definition at line 32 of file tree_node.cpp.

◆ getInput() [1/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 identifier (before remapping) of the port.
Returns
false if an error occurs.

Definition at line 232 of file tree_node.h.

◆ getInput() [2/2]

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

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

Definition at line 159 of file tree_node.h.

◆ getRawPortValue()

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

Definition at line 132 of file tree_node.cpp.

◆ getRemappedKey()

Optional< StringView > BT::TreeNode::getRemappedKey ( StringView  port_name,
StringView  remapping_value 
)
static

Definition at line 179 of file tree_node.cpp.

◆ halt()

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

◆ isBlackboardPointer()

bool BT::TreeNode::isBlackboardPointer ( StringView  str)
static

Check a string and return true if it matches either one of these two patterns: {...} or ${...}

Definition at line 145 of file tree_node.cpp.

◆ isHalted()

bool BT::TreeNode::isHalted ( ) const

Definition at line 106 of file tree_node.cpp.

◆ modifyPortsRemapping()

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

Definition at line 211 of file tree_node.cpp.

◆ name()

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

Name of the instance, not the type.

Definition at line 101 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 122 of file tree_node.cpp.

◆ resetStatus()

void BT::TreeNode::resetStatus ( )
protected

Equivalent to setStatus(NodeStatus::IDLE)

Definition at line 79 of file tree_node.cpp.

◆ setOutput()

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

Definition at line 293 of file tree_node.h.

◆ setPostTickOverrideFunction()

void BT::TreeNode::setPostTickOverrideFunction ( PostTickOverrideCallback  callback)

This method attaches to the TreeNode a callback with signature:

Optional<NodeStatus> myCallback(TreeNode& node, NodeStatus prev_status, NodeStatus tick_status)

This callback is executed AFTER the tick() and, if it returns a valid Optional<NodeStatus>, the value returned by the actual tick() is overriden with this one.

◆ setPreTickOverrideFunction()

void BT::TreeNode::setPreTickOverrideFunction ( PreTickOverrideCallback  callback)

This method attaches to the TreeNode a callback with signature:

 Optional<NodeStatus> myCallback(TreeNode& node, NodeStatus current_status)

This callback is executed BEFORE the tick() and, if it returns a valid Optional<NodeStatus>, 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

◆ setRegistrationID()

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

Definition at line 201 of file tree_node.cpp.

◆ setStatus()

void BT::TreeNode::setStatus ( NodeStatus  new_status)
protected

Definition at line 63 of file tree_node.cpp.

◆ setWakeUpInstance()

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

Definition at line 206 of file tree_node.cpp.

◆ status()

NodeStatus BT::TreeNode::status ( ) const

Definition at line 84 of file tree_node.cpp.

◆ stripBlackboardPointer()

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

Definition at line 162 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 112 of file tree_node.cpp.

◆ tick()

virtual BT::NodeStatus BT::TreeNode::tick ( )
protectedpure virtual

◆ type()

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

◆ UID()

uint16_t BT::TreeNode::UID ( ) const

Definition at line 117 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 90 of file tree_node.cpp.

Friends And Related Function Documentation

◆ BehaviorTreeFactory

friend class BehaviorTreeFactory
friend

Definition at line 189 of file tree_node.h.

◆ ControlNode

friend class ControlNode
friend

Definition at line 191 of file tree_node.h.

◆ DecoratorNode

friend class DecoratorNode
friend

Definition at line 190 of file tree_node.h.

◆ Tree

friend class Tree
friend

Definition at line 192 of file tree_node.h.

Member Data Documentation

◆ config_

NodeConfiguration BT::TreeNode::config_
private

Definition at line 219 of file tree_node.h.

◆ name_

const std::string BT::TreeNode::name_
private

Definition at line 207 of file tree_node.h.

◆ post_condition_callback_

PostTickOverrideCallback BT::TreeNode::post_condition_callback_
private

Definition at line 225 of file tree_node.h.

◆ pre_condition_callback_

PreTickOverrideCallback BT::TreeNode::pre_condition_callback_
private

Definition at line 223 of file tree_node.h.

◆ registration_ID_

std::string BT::TreeNode::registration_ID_
private

Definition at line 221 of file tree_node.h.

◆ state_change_signal_

StatusChangeSignal BT::TreeNode::state_change_signal_
private

Definition at line 215 of file tree_node.h.

◆ state_condition_variable_

std::condition_variable BT::TreeNode::state_condition_variable_
private

Definition at line 211 of file tree_node.h.

◆ state_mutex_

std::mutex BT::TreeNode::state_mutex_
mutableprivate

Definition at line 213 of file tree_node.h.

◆ status_

NodeStatus BT::TreeNode::status_
private

Definition at line 209 of file tree_node.h.

◆ uid_

const uint16_t BT::TreeNode::uid_
private

Definition at line 217 of file tree_node.h.

◆ wake_up_

std::shared_ptr<WakeUpSignal> BT::TreeNode::wake_up_
private

Definition at line 227 of file tree_node.h.


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


behaviortree_cpp_v3
Author(s): Michele Colledanchise, Davide Faconti
autogenerated on Mon Jul 3 2023 02:50:15