Namespaces | Classes | Typedefs | Enumerations | Functions | Variables
BT Namespace Reference

Namespaces

 details
 
 strings_internal
 

Classes

class  ActionNodeBase
 The ActionNodeBase is the base class to use to create any kind of action. A particular derived class is free to override executeTick() as needed. More...
 
class  AlwaysFailureNode
 
class  AlwaysSuccessNode
 
class  Any
 
class  AsyncActionNode
 The AsyncActionNode uses a different thread, where the action will be executed. More...
 
class  AsyncActionTest
 
class  BehaviorTreeException
 
class  BehaviorTreeFactory
 The BehaviorTreeFactory is used to create instances of a TreeNode at run-time. More...
 
class  Blackboard
 The Blackboard is the mechanism used by BehaviorTrees to exchange typed data. More...
 
class  BlackboardPreconditionNode
 
class  ConditionNode
 
class  ConditionTestNode
 
class  ControlNode
 
class  CoroActionNode
 The CoroActionNode class is an ideal candidate for asynchronous actions which need to communicate with an external service using an asynch request/reply interface (being notable examples ActionLib in ROS, MoveIt clients or move_base clients). More...
 
class  DecoratorNode
 
class  DelayNode
 The delay node will introduce a delay of a few milliseconds and then tick the child returning the status of the child as it is upon completion The delay is in milliseconds and it is passed using the port "delay_msec". More...
 
class  FallbackNode
 The FallbackNode is used to try different strategies, until one succeeds. If any child returns RUNNING, previous children will NOT be ticked again. More...
 
class  FileLogger
 
class  ForceFailureNode
 The ForceFailureNode returns always FAILURE or RUNNING. More...
 
class  ForceSuccessNode
 The ForceSuccessNode returns always SUCCESS or RUNNING. More...
 
struct  has_static_method_providedPorts
 
struct  has_static_method_providedPorts< T, typename std::enable_if< std::is_same< decltype(T::providedPorts()), PortsList >::value >::type >
 
class  IfThenElseNode
 IfThenElseNode must have exactly 2 or 3 children. This node is NOT reactive. More...
 
class  InverterNode
 The InverterNode returns SUCCESS if child fails of FAILURE is child succeeds. RUNNING status is propagated. More...
 
class  KeepRunningUntilFailureNode
 The KeepRunningUntilFailureNode returns always FAILURE or RUNNING. More...
 
class  LeafNode
 
class  LogicError
 
class  ManualSelectorNode
 Use a Terminal User Interface (ncurses) to select a certain child manually. More...
 
class  MinitraceLogger
 
struct  NodeConfiguration
 
class  ParallelNode
 
class  Parser
 The BehaviorTreeParser is a class used to read the model of a BehaviorTree from file or text and instantiate the corresponding tree using the BehaviorTreeFactory. More...
 
class  PortInfo
 
class  PublisherZMQ
 
class  ReactiveFallback
 The ReactiveFallback is similar to a ParallelNode. All the children are ticked from first to last: More...
 
class  ReactiveSequence
 The ReactiveSequence is similar to a ParallelNode. All the children are ticked from first to last: More...
 
class  RepeatNode
 The RepeatNode is used to execute a child several times, as long as it succeed. More...
 
class  RetryNode
 The RetryNode is used to execute a child several times if it fails. More...
 
class  RuntimeError
 
class  scoped_demangled_name
 
class  SequenceNode
 The SequenceNode is used to tick children in an ordered sequence. If any child returns RUNNING, previous children will NOT be ticked again. More...
 
class  SequenceStarNode
 The SequenceStarNode is used to tick children in an ordered sequence. If any child returns RUNNING, previous children are not ticked again. More...
 
class  SetBlackboard
 The SetBlackboard is action used to store a string into an entry of the Blackboard specified in "output_key". More...
 
class  SharedLibrary
 
class  Signal
 
class  SimpleActionNode
 The SimpleActionNode provides an easy to use SyncActionNode. The user should simply provide a callback with this signature. More...
 
class  SimpleConditionNode
 The SimpleConditionNode provides an easy to use ConditionNode. The user should simply provide a callback with this signature. More...
 
class  SimpleDecoratorNode
 The SimpleDecoratorNode provides an easy to use DecoratorNode. The user should simply provide a callback with this signature. More...
 
class  StatefulActionNode
 The ActionNode is the goto option for, but it is actually much easier to use correctly. More...
 
class  StatusChangeLogger
 
class  StdCoutLogger
 AddStdCoutLoggerToTree. Give the root node of a tree, a simple callback is subscribed to any status change of each node. More...
 
class  SubtreeNode
 The SubtreeNode is a way to wrap an entire Subtree, creating a separated BlackBoard. If you want to have data flow through ports, you need to explicitly remap the ports. More...
 
class  SubtreePlusNode
 The SubtreePlus is a new kind of subtree that gives you much more control over remapping: More...
 
class  SwitchNode
 The SwitchNode is equivalent to a switch statement, where a certain branch (child) is executed according to the value of a blackboard entry. More...
 
class  SyncActionNode
 The SyncActionNode is an ActionNode that explicitly prevents the status RUNNING and doesn't require an implementation of halt(). More...
 
class  SyncActionTest
 
class  TimeoutNode
 The TimeoutNode will halt() a running child if the latter has been RUNNING for more than a give time. The timeout is in milliseconds and it is passed using the port "msec". More...
 
class  TimerQueue
 
class  Tree
 Struct used to store a tree. If this object goes out of scope, the tree is destroyed. More...
 
class  TreeNode
 Abstract base class for Behavior Tree Nodes. More...
 
struct  TreeNodeManifest
 This information is used mostly by the XMLParser. More...
 
class  WhileDoElseNode
 WhileDoElse must have exactly 2 or 3 children. It is a REACTIVE node of IfThenElseNode. More...
 
class  XMLParser
 The XMLParser is a class used to read the model of a BehaviorTree from file or text and instantiate the corresponding tree using the BehaviorTreeFactory. More...
 

Typedefs

typedef std::chrono::high_resolution_clock::duration Duration
 
template<typename Predicate >
using enable_if = typename std::enable_if< Predicate::value >::type *
 
template<typename Predicate >
using enable_if_not = typename std::enable_if< !Predicate::value >::type *
 
template<typename T >
using has_default_constructor = typename std::is_constructible< T, const std::string & >
 
template<typename T >
using has_params_constructor = typename std::is_constructible< T, const std::string &, const NodeConfiguration & >
 
typedef std::function< std::unique_ptr< TreeNode >const std::string &, const NodeConfiguration &)> NodeBuilder
 The term "Builder" refers to the Builder Pattern (https://en.wikipedia.org/wiki/Builder_pattern) More...
 
template<typename T >
using Optional = nonstd::expected< T, std::string >
 
typedef std::unordered_map< std::string, PortInfoPortsList
 
typedef std::unordered_map< std::string, std::string > PortsRemapping
 
using Result = Optional< void >
 
typedef std::array< uint8_t, 12 > SerializedTransition
 
typedef std::vector< std::pair< uint16_t, uint8_t > > SerializedTreeStatus
 
typedef std::function< Any(StringView)> StringConverter
 
typedef std::unordered_map< const std::type_info *, StringConverterStringConvertersMap
 
typedef nonstd::string_view StringView
 
typedef std::chrono::high_resolution_clock::time_point TimePoint
 

Enumerations

enum  NodeStatus { NodeStatus::IDLE = 0, NodeStatus::RUNNING, NodeStatus::SUCCESS, NodeStatus::FAILURE }
 
enum  NodeType {
  NodeType::UNDEFINED = 0, NodeType::ACTION, NodeType::CONDITION, NodeType::CONTROL,
  NodeType::DECORATOR, NodeType::SUBTREE
}
 Enumerates the possible types of nodes. More...
 
enum  PortDirection { PortDirection::INPUT, PortDirection::OUTPUT, PortDirection::INOUT }
 
enum  TimestampType { TimestampType::absolute, TimestampType::relative }
 

Functions

void applyRecursiveVisitor (const TreeNode *root_node, const std::function< void(const TreeNode *)> &visitor)
 
void applyRecursiveVisitor (TreeNode *root_node, const std::function< void(TreeNode *)> &visitor)
 
template<typename T >
void assignDefaultRemapping (NodeConfiguration &config)
 
template<typename T = void>
std::pair< std::string, PortInfoBidirectionalPort (StringView name, StringView description={})
 
template<typename T = void>
std::pair< std::string, PortInfoBidirectionalPort (StringView name, const T &default_value, StringView description)
 
void buildSerializedStatusSnapshot (const TreeNode *root_node, SerializedTreeStatus &serialized_buffer)
 buildSerializedStatusSnapshot can be used to create a buffer that can be stored (or sent to a client application) to know the status of all the nodes of a tree. It is not "human readable". More...
 
void buildSerializedStatusSnapshot (TreeNode *root_node, SerializedTreeStatus &serialized_buffer)
 
Tree buildTreeFromFile (const BehaviorTreeFactory &factory, const std::string &filename, const Blackboard::Ptr &blackboard)
 
Tree buildTreeFromText (const BehaviorTreeFactory &factory, const std::string &text, const Blackboard::Ptr &blackboard)
 
template<>
Position2D convertFromString (StringView str)
 
template<>
Pose2D convertFromString (StringView key)
 
template<>
Point3D convertFromString (StringView key)
 
template<typename T >
convertFromString (StringView)
 
template<>
bool convertFromString< bool > (StringView str)
 
template<>
const char * convertFromString< const char * > (StringView str)
 
template<>
double convertFromString< double > (StringView str)
 
template<>
float convertFromString< float > (StringView str)
 
template<>
int convertFromString< int > (StringView str)
 
template<>
long convertFromString< long > (StringView str)
 
template<>
NodeStatus convertFromString< NodeStatus > (StringView str)
 
template<>
NodeType convertFromString< NodeType > (StringView str)
 
template<>
PortDirection convertFromString< PortDirection > (StringView str)
 
template<>
std::string convertFromString< std::string > (StringView str)
 
template<>
std::vector< double > convertFromString< std::vector< double > > (StringView str)
 
template<>
std::vector< int > convertFromString< std::vector< int > > (StringView str)
 
template<>
unsigned convertFromString< unsigned > (StringView str)
 
template<>
unsigned long convertFromString< unsigned long > (StringView str)
 
Serialization::NodeType convertToFlatbuffers (BT::NodeType type)
 
Serialization::NodeStatus convertToFlatbuffers (BT::NodeStatus type)
 
Serialization::PortDirection convertToFlatbuffers (BT::PortDirection direction)
 
template<typename T >
NodeBuilder CreateBuilder (typename std::enable_if< has_default_constructor< T >::value &&has_params_constructor< T >::value >::type *=nullptr)
 
template<typename T >
NodeBuilder CreateBuilder (typename std::enable_if<!has_default_constructor< T >::value &&has_params_constructor< T >::value >::type *=nullptr)
 
template<typename T >
NodeBuilder CreateBuilder (typename std::enable_if< has_default_constructor< T >::value &&!has_params_constructor< T >::value >::type *=nullptr)
 
void CreateFlatbuffersBehaviorTree (flatbuffers::FlatBufferBuilder &builder, const BT::Tree &tree)
 
template<typename T >
TreeNodeManifest CreateManifest (const std::string &ID, PortsList portlist=getProvidedPorts< T >())
 
template<typename T = void>
std::pair< std::string, PortInfoCreatePort (PortDirection direction, StringView name, StringView description={})
 
std::string demangle (char const *name)
 
std::string demangle (const std::type_info *info)
 
std::string demangle (const std::type_info &info)
 
char const * demangle_alloc (char const *name) noexcept
 
void demangle_free (char const *name) noexcept
 
template<typename T >
StringConverter GetAnyFromStringFunctor ()
 
template<>
StringConverter GetAnyFromStringFunctor< void > ()
 
template<typename T >
PortsList getProvidedPorts (enable_if< has_static_method_providedPorts< T > >=nullptr)
 
template<typename T >
PortsList getProvidedPorts (enable_if_not< has_static_method_providedPorts< T > >=nullptr)
 
template<typename T >
NodeType getType ()
 
static uint16_t getUID ()
 
template<typename T = void>
std::pair< std::string, PortInfoInputPort (StringView name, StringView description={})
 
template<typename T = void>
std::pair< std::string, PortInfoInputPort (StringView name, const T &default_value, StringView description)
 
std::ostream & operator<< (std::ostream &os, const BT::NodeStatus &status)
 
std::ostream & operator<< (std::ostream &os, const BT::NodeType &type)
 
std::ostream & operator<< (std::ostream &os, const BT::PortDirection &type)
 
template<typename T = void>
std::pair< std::string, PortInfoOutputPort (StringView name, StringView description={})
 
void printTreeRecursively (const TreeNode *root_node, std::ostream &stream=std::cout)
 
SerializedTransition SerializeTransition (uint16_t UID, Duration timestamp, NodeStatus prev_status, NodeStatus status)
 
std::vector< StringViewsplitString (const StringView &strToSplit, char delimeter)
 
void StrAppend (std::string *destination, const nonstd::string_view &a)
 
void StrAppend (std::string *destination, const nonstd::string_view &a, const nonstd::string_view &b)
 
void StrAppend (std::string *destination, const nonstd::string_view &a, const nonstd::string_view &b, const nonstd::string_view &c)
 
template<typename... AV>
void StrAppend (std::string *destination, const nonstd::string_view &a, const nonstd::string_view &b, const nonstd::string_view &c, const nonstd::string_view &d, const AV &...args)
 
std::string StrCat ()
 
std::string StrCat (const nonstd::string_view &a)
 
std::string StrCat (const nonstd::string_view &a, const nonstd::string_view &b)
 
std::string StrCat (const nonstd::string_view &a, const nonstd::string_view &b, const nonstd::string_view &c)
 
template<typename... AV>
std::string StrCat (const nonstd::string_view &a, const nonstd::string_view &b, const nonstd::string_view &c, const nonstd::string_view &d, const AV &...args)
 
const char * toConstStr (NodeType type)
 
template<typename T >
std::string toStr (T value)
 
std::string toStr (std::string value)
 
std::string toStr (BT::NodeStatus status, bool colored)
 toStr converts NodeStatus to string. Optionally colored. More...
 
template<>
std::string toStr< BT::NodeStatus > (BT::NodeStatus status)
 
template<>
std::string toStr< BT::NodeType > (BT::NodeType type)
 toStr converts NodeType to string. More...
 
template<>
std::string toStr< BT::PortDirection > (BT::PortDirection direction)
 
template<>
std::string toStr< NodeStatus > (NodeStatus status)
 
template<>
std::string toStr< NodeType > (NodeType type)
 
template<>
std::string toStr< PortDirection > (PortDirection direction)
 
void VerifyXML (const std::string &xml_text, const std::set< std::string > &registered_nodes)
 
std::string writeTreeNodesModelXML (const BehaviorTreeFactory &factory)
 

Variables

constexpr const char * PLUGIN_SYMBOL = "BT_RegisterNodesFromPlugin"
 
auto StrEqual
 

Typedef Documentation

typedef std::chrono::high_resolution_clock::duration BT::Duration

Definition at line 340 of file basic_types.h.

template<typename Predicate >
using BT::enable_if = typedef typename std::enable_if< Predicate::value >::type*

Definition at line 168 of file basic_types.h.

template<typename Predicate >
using BT::enable_if_not = typedef typename std::enable_if< !Predicate::value >::type*

Definition at line 171 of file basic_types.h.

template<typename T >
using BT::has_default_constructor = typedef typename std::is_constructible<T, const std::string&>

Definition at line 36 of file bt_factory.h.

template<typename T >
using BT::has_params_constructor = typedef typename std::is_constructible<T, const std::string&, const NodeConfiguration&>

Definition at line 39 of file bt_factory.h.

typedef std::function<std::unique_ptr<TreeNode>const std::string&, const NodeConfiguration&)> BT::NodeBuilder

The term "Builder" refers to the Builder Pattern (https://en.wikipedia.org/wiki/Builder_pattern)

Definition at line 33 of file bt_factory.h.

template<typename T >
using BT::Optional = typedef nonstd::expected<T, std::string>

Usage: given a function/method like:

Optional<double> getAnswer();

User code can check result and error message like this:

auto res = getAnswer();
if( res )
{
    std::cout << "answer was: " << res.value() << std::endl;
}
else{
    std::cerr << "failed to get the answer: " << res.error() << std::endl;
}

Definition at line 190 of file basic_types.h.

typedef std::unordered_map<std::string, PortInfo> BT::PortsList

Definition at line 317 of file basic_types.h.

typedef std::unordered_map<std::string, std::string> BT::PortsRemapping

Definition at line 39 of file tree_node.h.

using BT::Result = typedef Optional<void>

Usage: given a function/method like:

Result DoSomething();

User code can check result and error message like this:

auto res = DoSomething();
if( res )
{
    std::cout << "DoSomething() done " << std::endl;
}
else{
    std::cerr << "DoSomething() failed with message: " << res.error() << std::endl;
}

Definition at line 210 of file basic_types.h.

typedef std::array< uint8_t, 12 > BT::SerializedTransition

Definition at line 10 of file bt_flatbuffer_helper.h.

typedef std::vector<std::pair<uint16_t, uint8_t> > BT::SerializedTreeStatus

Definition at line 64 of file behavior_tree.h.

typedef std::function<Any(StringView)> BT::StringConverter

Definition at line 115 of file basic_types.h.

typedef std::unordered_map<const std::type_info*, StringConverter> BT::StringConvertersMap

Definition at line 117 of file basic_types.h.

typedef nonstd::string_view BT::StringView

Definition at line 50 of file basic_types.h.

typedef std::chrono::high_resolution_clock::time_point BT::TimePoint

Definition at line 339 of file basic_types.h.

Enumeration Type Documentation

enum BT::NodeStatus
strong

Enumerates the states every node can be in after execution during a particular time step. IMPORTANT: Your custom nodes should NEVER return IDLE.

Enumerator
IDLE 
RUNNING 
SUCCESS 
FAILURE 

Definition at line 35 of file basic_types.h.

enum BT::NodeType
strong

Enumerates the possible types of nodes.

Enumerator
UNDEFINED 
ACTION 
CONDITION 
CONTROL 
DECORATOR 
SUBTREE 

Definition at line 22 of file basic_types.h.

enum BT::PortDirection
strong
Enumerator
INPUT 
OUTPUT 
INOUT 

Definition at line 43 of file basic_types.h.

enum BT::TimestampType
strong
Enumerator
absolute 
relative 

Definition at line 9 of file abstract_logger.h.

Function Documentation

void BT::applyRecursiveVisitor ( const TreeNode root_node,
const std::function< void(const TreeNode *)> &  visitor 
)

Definition at line 18 of file behavior_tree.cpp.

void BT::applyRecursiveVisitor ( TreeNode root_node,
const std::function< void(TreeNode *)> &  visitor 
)

Definition at line 41 of file behavior_tree.cpp.

template<typename T >
void BT::assignDefaultRemapping ( NodeConfiguration config)
inline

Definition at line 275 of file tree_node.h.

template<typename T = void>
std::pair<std::string,PortInfo> BT::BidirectionalPort ( StringView  name,
StringView  description = {} 
)
inline

Definition at line 295 of file basic_types.h.

template<typename T = void>
std::pair<std::string,PortInfo> BT::BidirectionalPort ( StringView  name,
const T &  default_value,
StringView  description 
)
inline

Definition at line 309 of file basic_types.h.

void BT::buildSerializedStatusSnapshot ( const TreeNode root_node,
SerializedTreeStatus serialized_buffer 
)

buildSerializedStatusSnapshot can be used to create a buffer that can be stored (or sent to a client application) to know the status of all the nodes of a tree. It is not "human readable".

Parameters
root_node
serialized_bufferis the output.
void BT::buildSerializedStatusSnapshot ( TreeNode root_node,
SerializedTreeStatus serialized_buffer 
)

Definition at line 100 of file behavior_tree.cpp.

Tree BT::buildTreeFromFile ( const BehaviorTreeFactory factory,
const std::string &  filename,
const Blackboard::Ptr blackboard 
)

Definition at line 837 of file xml_parsing.cpp.

Tree BT::buildTreeFromText ( const BehaviorTreeFactory factory,
const std::string &  text,
const Blackboard::Ptr blackboard 
)

Definition at line 829 of file xml_parsing.cpp.

template<>
Position2D BT::convertFromString ( StringView  str)
inline

Definition at line 17 of file t03_generic_ports.cpp.

template<>
Pose2D BT::convertFromString ( StringView  key)
inline

Definition at line 26 of file movebase_node.h.

template<>
Point3D BT::convertFromString ( StringView  key)

Definition at line 28 of file t07_wrap_legacy.cpp.

template<typename T >
T BT::convertFromString ( StringView  )
inline

convertFromString is used to convert a string into a custom type.

This function is invoked under the hood by TreeNode::getInput(), but only when the input port contains a string.

If you have a custom type, you need to implement the corresponding template specialization.

Definition at line 61 of file basic_types.h.

template<>
bool BT::convertFromString< bool > ( StringView  str)

Definition at line 180 of file basic_types.cpp.

template<>
const char* BT::convertFromString< const char * > ( StringView  str)
template<>
double BT::convertFromString< double > ( StringView  str)

Definition at line 129 of file basic_types.cpp.

template<>
float BT::convertFromString< float > ( StringView  str)

Definition at line 142 of file basic_types.cpp.

template<>
int BT::convertFromString< int > ( StringView  str)

Definition at line 105 of file basic_types.cpp.

template<>
long BT::convertFromString< long > ( StringView  str)

Definition at line 111 of file basic_types.cpp.

Definition at line 211 of file basic_types.cpp.

Definition at line 221 of file basic_types.cpp.

Definition at line 232 of file basic_types.cpp.

template<>
std::string BT::convertFromString< std::string > ( StringView  str)

Definition at line 98 of file basic_types.cpp.

template<>
std::vector< double > BT::convertFromString< std::vector< double > > ( StringView  str)

Definition at line 166 of file basic_types.cpp.

template<>
std::vector< int > BT::convertFromString< std::vector< int > > ( StringView  str)

Definition at line 152 of file basic_types.cpp.

template<>
unsigned BT::convertFromString< unsigned > ( StringView  str)

Definition at line 117 of file basic_types.cpp.

template<>
unsigned long BT::convertFromString< unsigned long > ( StringView  str)

Definition at line 123 of file basic_types.cpp.

Serialization::NodeType BT::convertToFlatbuffers ( BT::NodeType  type)
inline

Definition at line 12 of file bt_flatbuffer_helper.h.

Serialization::NodeStatus BT::convertToFlatbuffers ( BT::NodeStatus  type)
inline

Definition at line 32 of file bt_flatbuffer_helper.h.

Serialization::PortDirection BT::convertToFlatbuffers ( BT::PortDirection  direction)
inline

Definition at line 48 of file bt_flatbuffer_helper.h.

template<typename T >
NodeBuilder BT::CreateBuilder ( typename std::enable_if< has_default_constructor< T >::value &&has_params_constructor< T >::value >::type *  = nullptr)
inline

Definition at line 43 of file bt_factory.h.

template<typename T >
NodeBuilder BT::CreateBuilder ( typename std::enable_if<!has_default_constructor< T >::value &&has_params_constructor< T >::value >::type *  = nullptr)
inline

Definition at line 60 of file bt_factory.h.

template<typename T >
NodeBuilder BT::CreateBuilder ( typename std::enable_if< has_default_constructor< T >::value &&!has_params_constructor< T >::value >::type *  = nullptr)
inline

Definition at line 70 of file bt_factory.h.

void BT::CreateFlatbuffersBehaviorTree ( flatbuffers::FlatBufferBuilder builder,
const BT::Tree tree 
)
inline

Definition at line 62 of file bt_flatbuffer_helper.h.

template<typename T >
TreeNodeManifest BT::CreateManifest ( const std::string &  ID,
PortsList  portlist = getProvidedPorts<T>() 
)
inline

Definition at line 81 of file bt_factory.h.

template<typename T = void>
std::pair<std::string,PortInfo> BT::CreatePort ( PortDirection  direction,
StringView  name,
StringView  description = {} 
)

Definition at line 260 of file basic_types.h.

std::string BT::demangle ( char const *  name)
inline

Definition at line 78 of file demangle_util.h.

std::string BT::demangle ( const std::type_info *  info)
inline

Definition at line 85 of file demangle_util.h.

std::string BT::demangle ( const std::type_info &  info)
inline

Definition at line 107 of file demangle_util.h.

char const * BT::demangle_alloc ( char const *  name)
inlinenoexcept

Definition at line 69 of file demangle_util.h.

void BT::demangle_free ( char const *  name)
inlinenoexcept

Definition at line 74 of file demangle_util.h.

template<typename T >
StringConverter BT::GetAnyFromStringFunctor ( )
inline

Definition at line 122 of file basic_types.h.

template<>
StringConverter BT::GetAnyFromStringFunctor< void > ( )
inline

Definition at line 128 of file basic_types.h.

template<typename T >
PortsList BT::getProvidedPorts ( enable_if< has_static_method_providedPorts< T > >  = nullptr)
inline

Definition at line 328 of file basic_types.h.

template<typename T >
PortsList BT::getProvidedPorts ( enable_if_not< has_static_method_providedPorts< T > >  = nullptr)
inline

Definition at line 334 of file basic_types.h.

template<typename T >
NodeType BT::getType ( )
inline

Simple way to extract the type of a TreeNode at COMPILE TIME. Useful to avoid the cost of dynamic_cast or the virtual method TreeNode::type().

Definition at line 80 of file behavior_tree.h.

static uint16_t BT::getUID ( )
static

Definition at line 19 of file tree_node.cpp.

template<typename T = void>
std::pair<std::string,PortInfo> BT::InputPort ( StringView  name,
StringView  description = {} 
)
inline

Definition at line 283 of file basic_types.h.

template<typename T = void>
std::pair<std::string,PortInfo> BT::InputPort ( StringView  name,
const T &  default_value,
StringView  description 
)
inline

Definition at line 301 of file basic_types.h.

std::ostream & BT::operator<< ( std::ostream &  os,
const BT::NodeStatus status 
)

Definition at line 246 of file basic_types.cpp.

std::ostream & BT::operator<< ( std::ostream &  os,
const BT::NodeType type 
)

Definition at line 240 of file basic_types.cpp.

std::ostream & BT::operator<< ( std::ostream &  os,
const BT::PortDirection type 
)

Definition at line 252 of file basic_types.cpp.

template<typename T = void>
std::pair<std::string,PortInfo> BT::OutputPort ( StringView  name,
StringView  description = {} 
)
inline

Definition at line 289 of file basic_types.h.

void BT::printTreeRecursively ( const TreeNode root_node,
std::ostream &  stream = std::cout 
)

Debug function to print the hierarchy of the tree. Prints to std::cout by default.

Definition at line 65 of file behavior_tree.cpp.

SerializedTransition BT::SerializeTransition ( uint16_t  UID,
Duration  timestamp,
NodeStatus  prev_status,
NodeStatus  status 
)
inline

Serialize manually the informations about state transition No flatbuffer serialization here

Definition at line 148 of file bt_flatbuffer_helper.h.

std::vector< StringView > BT::splitString ( const StringView strToSplit,
char  delimeter 
)

Definition at line 258 of file basic_types.cpp.

void BT::StrAppend ( std::string *  destination,
const nonstd::string_view &  a 
)
inline

Definition at line 80 of file strcat.hpp.

void BT::StrAppend ( std::string *  destination,
const nonstd::string_view &  a,
const nonstd::string_view &  b 
)
inline

Definition at line 86 of file strcat.hpp.

void BT::StrAppend ( std::string *  destination,
const nonstd::string_view &  a,
const nonstd::string_view &  b,
const nonstd::string_view &  c 
)
inline

Definition at line 93 of file strcat.hpp.

template<typename... AV>
void BT::StrAppend ( std::string *  destination,
const nonstd::string_view &  a,
const nonstd::string_view &  b,
const nonstd::string_view &  c,
const nonstd::string_view &  d,
const AV &...  args 
)
inline

Definition at line 103 of file strcat.hpp.

std::string BT::StrCat ( )
inline

Definition at line 47 of file strcat.hpp.

std::string BT::StrCat ( const nonstd::string_view &  a)
inline

Definition at line 49 of file strcat.hpp.

std::string BT::StrCat ( const nonstd::string_view &  a,
const nonstd::string_view &  b 
)
inline

Definition at line 53 of file strcat.hpp.

std::string BT::StrCat ( const nonstd::string_view &  a,
const nonstd::string_view &  b,
const nonstd::string_view &  c 
)
inline

Definition at line 59 of file strcat.hpp.

template<typename... AV>
std::string BT::StrCat ( const nonstd::string_view &  a,
const nonstd::string_view &  b,
const nonstd::string_view &  c,
const nonstd::string_view &  d,
const AV &...  args 
)
inline

Definition at line 68 of file strcat.hpp.

const char* BT::toConstStr ( NodeType  type)

Definition at line 30 of file bt_minitrace_logger.cpp.

template<typename T >
std::string BT::toStr ( value)

Definition at line 136 of file basic_types.h.

std::string BT::toStr ( std::string  value)

Definition at line 26 of file basic_types.cpp.

std::string BT::toStr ( BT::NodeStatus  status,
bool  colored 
)

toStr converts NodeStatus to string. Optionally colored.

Definition at line 31 of file basic_types.cpp.

template<>
std::string BT::toStr< BT::NodeStatus > ( BT::NodeStatus  status)
template<>
std::string BT::toStr< BT::NodeType > ( BT::NodeType  type)

toStr converts NodeType to string.

template<>
std::string BT::toStr< BT::PortDirection > ( BT::PortDirection  direction)
template<>
std::string BT::toStr< NodeStatus > ( NodeStatus  status)

Definition at line 10 of file basic_types.cpp.

template<>
std::string BT::toStr< NodeType > ( NodeType  type)

Definition at line 77 of file basic_types.cpp.

template<>
std::string BT::toStr< PortDirection > ( PortDirection  direction)

Definition at line 65 of file basic_types.cpp.

void BT::VerifyXML ( const std::string &  xml_text,
const std::set< std::string > &  registered_nodes 
)

Definition at line 202 of file xml_parsing.cpp.

std::string BT::writeTreeNodesModelXML ( const BehaviorTreeFactory factory)

Definition at line 761 of file xml_parsing.cpp.

Variable Documentation

constexpr const char* BT::PLUGIN_SYMBOL = "BT_RegisterNodesFromPlugin"

Definition at line 87 of file bt_factory.h.

auto BT::StrEqual
Initial value:
= [](const char* str1, const char* str2) -> bool {
return strcmp(str1, str2) == 0;
}

Definition at line 40 of file xml_parsing.cpp.



behaviotree_cpp_v3
Author(s): Michele Colledanchise, Davide Faconti
autogenerated on Tue May 4 2021 02:56:26