Public Types | Public Member Functions | Static Public Member Functions | Protected Member Functions | Private Attributes | Friends
BT::TreeNode Class Reference

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

#include <tree_node.h>

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

List of all members.

Public Types

typedef std::shared_ptr< TreeNodePtr

Public Member Functions

const NodeConfigurationconfig () const
virtual BT::NodeStatus executeTick ()
 The method that should be used to invoke tick() and setStatus();.
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.
const std::string & registrationName () const
 registrationName is the ID used by BehaviorTreeFactory to create an instance.
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.
 TreeNode (std::string name, NodeConfiguration config)
 TreeNode main constructor.
virtual NodeType type () const =0
uint16_t UID () const
BT::NodeStatus waitValidStatus ()
virtual ~TreeNode ()

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 setRegistrationID (StringView ID)
virtual BT::NodeStatus tick ()=0
 Method to be implemented by the user.

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

Detailed Description

Abstract base class for Behavior Tree Nodes.

Definition at line 53 of file tree_node.h.


Member Typedef Documentation

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

Definition at line 56 of file tree_node.h.


Constructor & Destructor Documentation

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.

virtual BT::TreeNode::~TreeNode ( ) [virtual]

Member Function Documentation

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

Definition at line 99 of file tree_node.cpp.

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.

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 185 of file tree_node.h.

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 133 of file tree_node.h.

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

Definition at line 134 of file tree_node.cpp.

virtual void BT::TreeNode::halt ( ) [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, 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.

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.

void BT::TreeNode::modifyPortsRemapping ( const PortsRemapping new_remapping) [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.

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

Definition at line 236 of file tree_node.h.

void BT::TreeNode::setRegistrationID ( StringView  ID) [inline, protected]

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.

Definition at line 56 of file tree_node.cpp.

Definition at line 119 of file tree_node.cpp.

TreeNode::StatusChangeSubscriber BT::TreeNode::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.

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

Definition at line 84 of file tree_node.cpp.

virtual BT::NodeStatus BT::TreeNode::tick ( ) [protected, pure virtual]
virtual NodeType BT::TreeNode::type ( ) const [pure virtual]
uint16_t BT::TreeNode::UID ( ) const

Definition at line 89 of file tree_node.cpp.

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.


Friends And Related Function Documentation

friend class BehaviorTreeFactory [friend]

Definition at line 155 of file tree_node.h.


Member Data Documentation

Definition at line 178 of file tree_node.h.

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

Definition at line 166 of file tree_node.h.

std::string BT::TreeNode::registration_ID_ [private]

Definition at line 180 of file tree_node.h.

StatusChangeSignal BT::TreeNode::state_change_signal_ [private]

Definition at line 174 of file tree_node.h.

std::condition_variable BT::TreeNode::state_condition_variable_ [private]

Definition at line 170 of file tree_node.h.

std::mutex BT::TreeNode::state_mutex_ [mutable, private]

Definition at line 172 of file tree_node.h.

Definition at line 168 of file tree_node.h.

const uint16_t BT::TreeNode::uid_ [private]

Definition at line 176 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 Jun 8 2019 20:17:15