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

#include <tree_node.h>

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

Public Types

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 Blackboard::Ptrblackboard () const
 
virtual BT::NodeStatus executeTick ()
 The method that will be executed to invoke tick(); and setStatus();. More...
 
template<typename T >
BT::optional< T > getParam (const std::string &key) const
 
template<typename T >
bool getParam (const std::string &key, T &destination) const
 
virtual void halt ()=0
 The method used to interrupt the execution of a RUNNING node. More...
 
const NodeParametersinitializationParameters () const
 
bool isHalted () const
 
const std::string & name () const
 
const std::string & registrationName () const
 registrationName is the ID used by BehaviorTreeFactory to create an instance. More...
 
void setBlackboard (const Blackboard::Ptr &bb)
 
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 (const std::string &name, const NodeParameters &parameters)
 TreeNode main constructor. More...
 
virtual NodeType type () const =0
 
uint16_t UID () const
 
BT::NodeStatus waitValidStatus ()
 
virtual ~TreeNode ()=default
 

Static Public Member Functions

static bool isBlackboardPattern (StringView str)
 

Protected Member Functions

void initializeOnce ()
 
void setRegistrationName (const std::string &registration_name)
 registrationName() is set by the BehaviorTreeFactory More...
 
virtual BT::NodeStatus tick ()=0
 Method to be implemented by the user. More...
 

Private Member Functions

virtual void onInit ()
 

Private Attributes

Blackboard::Ptr bb_
 
const std::string name_
 
bool not_initialized_
 
const NodeParameters parameters_
 
std::string registration_name_
 
StatusChangeSignal state_change_signal_
 
std::condition_variable state_condition_variable_
 
std::mutex state_mutex_
 
NodeStatus status_
 
const uint16_t uid_
 

Friends

class BehaviorTreeFactory
 

Detailed Description

Definition at line 39 of file tree_node.h.

Member Typedef Documentation

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

Definition at line 63 of file tree_node.h.

Definition at line 91 of file tree_node.h.

Definition at line 89 of file tree_node.h.

Definition at line 90 of file tree_node.h.

Constructor & Destructor Documentation

BT::TreeNode::TreeNode ( const std::string &  name,
const NodeParameters parameters 
)

TreeNode main constructor.

Parameters
namename of the instance, not the type of sensor.
parametersthis might be empty. use getParam<T>(key) to parse the value.

Note: a node that accepts a not empty set of NodeParameters must also implement the method:

static const NodeParameters& requiredNodeParameters();

Definition at line 25 of file tree_node.cpp.

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

Member Function Documentation

const Blackboard::Ptr & BT::TreeNode::blackboard ( ) const

Definition at line 64 of file tree_node.cpp.

NodeStatus BT::TreeNode::executeTick ( )
virtual

The method that will be executed to invoke tick(); and setStatus();.

Reimplemented in BT::CoroActionNode, BT::AsyncActionNode, BT::SyncActionNode, BT::ActionNodeBase, and BT::DecoratorNode.

Definition at line 35 of file tree_node.cpp.

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

Get a parameter from the NodeParameters and convert it to type T.

Definition at line 117 of file tree_node.h.

template<typename T >
bool BT::TreeNode::getParam ( const std::string &  key,
T &  destination 
) const
inline

Get a parameter from the passed NodeParameters and convert it to type T. Return false either if there is no parameter with this key or if conversion failed.

Definition at line 170 of file tree_node.h.

virtual void BT::TreeNode::halt ( )
pure virtual
const NodeParameters & BT::TreeNode::initializationParameters ( ) const

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

Definition at line 137 of file tree_node.cpp.

void BT::TreeNode::initializeOnce ( )
protected

Definition at line 118 of file tree_node.cpp.

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

Definition at line 127 of file tree_node.cpp.

bool BT::TreeNode::isHalted ( ) const

Definition at line 97 of file tree_node.cpp.

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

Definition at line 92 of file tree_node.cpp.

virtual void BT::TreeNode::onInit ( )
inlineprivatevirtual

This calback will be executed only ONCE after the constructor of the node, before the very first tick. Override if necessary.

Reimplemented in InitTestNode.

Definition at line 47 of file tree_node.h.

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

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

Definition at line 132 of file tree_node.cpp.

void BT::TreeNode::setBlackboard ( const Blackboard::Ptr bb)

Definition at line 59 of file tree_node.cpp.

void BT::TreeNode::setRegistrationName ( const std::string &  registration_name)
protected

registrationName() is set by the BehaviorTreeFactory

Definition at line 113 of file tree_node.cpp.

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

Definition at line 43 of file tree_node.cpp.

NodeStatus BT::TreeNode::status ( ) const

Definition at line 75 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.

Parameters
callback.Must have signature void funcname(NodeStatus prev_status, NodeStatus new_status)
Returns
the subscriber.

Definition at line 103 of file tree_node.cpp.

virtual BT::NodeStatus BT::TreeNode::tick ( )
protectedpure virtual
virtual NodeType BT::TreeNode::type ( ) const
pure virtual
uint16_t BT::TreeNode::UID ( ) const

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

Friends And Related Function Documentation

friend class BehaviorTreeFactory
friend

Definition at line 138 of file tree_node.h.

Member Data Documentation

Blackboard::Ptr BT::TreeNode::bb_
private

Definition at line 162 of file tree_node.h.

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

Definition at line 146 of file tree_node.h.

bool BT::TreeNode::not_initialized_
private

Definition at line 144 of file tree_node.h.

const NodeParameters BT::TreeNode::parameters_
private

Definition at line 160 of file tree_node.h.

std::string BT::TreeNode::registration_name_
private

Definition at line 158 of file tree_node.h.

StatusChangeSignal BT::TreeNode::state_change_signal_
private

Definition at line 154 of file tree_node.h.

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

Definition at line 150 of file tree_node.h.

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

Definition at line 152 of file tree_node.h.

NodeStatus BT::TreeNode::status_
private

Definition at line 148 of file tree_node.h.

const uint16_t BT::TreeNode::uid_
private

Definition at line 156 of file tree_node.h.


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


behaviortree_cpp
Author(s): Michele Colledanchise, Davide Faconti
autogenerated on Sat Feb 2 2019 04:01:55