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

Namespaces

 Ast
 
 details
 The SwitchNode is equivalent to a switch statement, where a certain branch (child) is executed according to the value of a blackboard entry.
 
 Grammar
 
 Monitor
 
 strings_internal
 
 test
 

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
 
struct  AnyTypeAllowed
 
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  ConditionNode
 
class  ConditionTestNode
 
class  ConsumeQueue
 
class  ControlNode
 
class  CoroActionNode
 The CoroActionNode class is an a good candidate for asynchronous actions which need to communicate with an external service using an async request/reply interface. More...
 
class  DecoratorNode
 
class  DelayNode
 The delay node will introduce a delay 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  EntryUpdatedAction
 The EntryUpdatedAction checks the Timestamp in an entry to determine if the value was updated since the last time. More...
 
class  EntryUpdatedDecorator
 The EntryUpdatedDecorator checks the Timestamp in an entry to determine if the value was updated since the last time (true, the first time). 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  FileLogger2
 The FileLogger2 is a logger that saves the tree as XML and all the transitions. Data is written to file in a separate thread, to minimize latency. More...
 
class  ForceFailureNode
 The ForceFailureNode returns always FAILURE or RUNNING. More...
 
class  ForceSuccessNode
 The ForceSuccessNode returns always SUCCESS or RUNNING. More...
 
class  Groot2Publisher
 The Groot2Publisher is used to create an interface between your BT.CPP executor and Groot2. More...
 
struct  has_static_method_metadata
 
struct  has_static_method_metadata< T, typename std::enable_if< std::is_same< decltype(T::metadata()), KeyValueVector >::value >::type >
 
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  JsonExporter
 
class  KeepRunningUntilFailureNode
 The KeepRunningUntilFailureNode returns always FAILURE or RUNNING. More...
 
class  LeafNode
 
class  LockedPtr
 The LockedPtr class is used to share a pointer to an object and a mutex that protects the read/write access to that object. More...
 
class  LogicError
 
class  LoopNode
 The LoopNode class is used to pop_front elements from a std::deque. This element is copied into the port "value" and the child will be executed, as long as we have elements in the queue. More...
 
class  ManualSelectorNode
 Use a Terminal User Interface (ncurses) to select a certain child manually. More...
 
class  MinitraceLogger
 
struct  NodeConfig
 
class  ParallelAllNode
 The ParallelAllNode execute all its children concurrently, but not in separate threads! More...
 
class  ParallelNode
 The ParallelNode execute all its children concurrently, but not in separate threads! More...
 
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  PopFromQueue
 
class  PortInfo
 
class  PreconditionNode
 
struct  ProtectedQueue
 
class  QueueSize
 
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  RetryNodeTypo
 
class  RunOnceNode
 The RunOnceNode is used when you want to execute the child only once. If the child is asynchronous, we will tick until either SUCCESS or FAILURE is returned. More...
 
class  RuntimeError
 
class  scoped_demangled_name
 
class  ScriptCondition
 Execute a script, and if the result is true, return SUCCESS, FAILURE otherwise. More...
 
class  ScriptNode
 
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  SequenceWithMemory
 The SequenceWithMemory is used to tick children in an ordered sequence. If any child returns RUNNING, previous children are not ticked again. More...
 
class  SetBlackboardNode
 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  SleepNode
 Sleep for a certain amount of time. Consider also using the decorator <Delay> More...
 
class  SqliteLogger
 The SqliteLogger is a logger that will store the tree and all the status transitions in a SQLite database (single file). More...
 
struct  StampedValue
 
class  StatefulActionNode
 The StatefulActionNode is the preferred way to implement asynchronous Actions. It is actually easier to use correctly, when compared with ThreadedAction. More...
 
class  StatusChangeLogger
 
class  StdCoutLogger
 StdCoutLogger is a very simple logger that displays all the transitions on the console. More...
 
struct  SubtreeModel
 
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  SwitchNode
 
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  TestNode
 The TestNode is a Node that can be configure to: More...
 
struct  TestNodeConfig
 
class  ThreadedAction
 The ThreadedAction executes the tick in a different thread. More...
 
class  TimeoutNode
 The TimeoutNode will halt() a running child if the latter has been RUNNING longer than a given time. The timeout is in milliseconds and it is passed using the port "msec". More...
 
class  TimerQueue
 
struct  Timestamp
 
struct  Transition
 
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  TreeObserver
 The TreeObserver is used to collect statistics about which nodes are executed and their returned status. More...
 
class  TypeInfo
 
class  UnsetBlackboardNode
 
class  WakeUpSignal
 
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

using AnyPtrLocked = LockedPtr< Any >
 
using Duration = std::chrono::high_resolution_clock::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 *
 
using EnumsTable = std::unordered_map< std::string, int >
 
using EnumsTablePtr = std::shared_ptr< EnumsTable >
 
using ErrorReport = lexy_ext::_report_error< char * >
 
template<typename T >
using Expected = nonstd::expected< T, std::string >
 
using KeyValueVector = std::vector< std::pair< std::string, std::string > >
 
using NodeBuilder = std::function< std::unique_ptr< TreeNode >(const std::string &, const NodeConfig &)>
 The term "Builder" refers to the Builder Pattern (https://en.wikipedia.org/wiki/Builder_pattern) More...
 
using NodeConfiguration = NodeConfig
 
using PortsList = std::unordered_map< std::string, PortInfo >
 
using PortsRemapping = std::unordered_map< std::string, std::string >
 
using Result = Expected< std::monostate >
 
using ScriptFunction = std::function< Any(Ast::Environment &env)>
 
using ScriptingEnumsRegistry = std::unordered_map< std::string, int >
 
using SerializedTransition = std::array< uint8_t, 12 >
 
using SerializedTreeStatus = std::vector< std::pair< uint16_t, uint8_t > >
 
template<typename T >
using SharedQueue = std::shared_ptr< std::deque< T > >
 
using StringConverter = std::function< Any(StringView)>
 
using StringConvertersMap = std::unordered_map< const std::type_info *, StringConverter >
 
using StringView = std::string_view
 
using TimePoint = std::chrono::high_resolution_clock::time_point
 

Enumerations

enum  { IDLE_FROM_SUCCESS = 10 + static_cast<int>(NodeStatus::SUCCESS), IDLE_FROM_FAILURE = 10 + static_cast<int>(NodeStatus::FAILURE), IDLE_FROM_RUNNING = 10 + static_cast<int>(NodeStatus::RUNNING) }
 
enum  NodeStatus {
  NodeStatus::IDLE = 0, NodeStatus::RUNNING = 1, NodeStatus::SUCCESS = 2, NodeStatus::FAILURE = 3,
  NodeStatus::SKIPPED = 4
}
 
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  PostCond {
  PostCond::ON_HALTED = 0, PostCond::ON_FAILURE, PostCond::ON_SUCCESS, PostCond::ALWAYS,
  PostCond::COUNT_
}
 
enum  PreCond {
  PreCond::FAILURE_IF = 0, PreCond::SUCCESS_IF, PreCond::SKIP_IF, PreCond::WHILE_TRUE,
  PreCond::COUNT_
}
 
enum  TimestampType { TimestampType::absolute, TimestampType::relative }
 

Functions

void addNodeModelToXML (const TreeNodeManifest &model, XMLDocument &doc, XMLElement *model_root)
 
void addTreeToXML (const Tree &tree, XMLDocument &doc, XMLElement *rootXML, bool add_metadata, bool add_builtin_models)
 
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 (NodeConfig &config)
 
template<typename T = AnyTypeAllowed, typename DefaultT = T>
std::pair< std::string, PortInfoBidirectionalPort (StringView name, const DefaultT &default_value, StringView description)
 
template<typename T = AnyTypeAllowed>
std::pair< std::string, PortInfoBidirectionalPort (StringView name, StringView description={})
 
std::vector< Blackboard::PtrBlackboardBackup (const BT::Tree &tree)
 BlackboardBackup uses Blackboard::cloneInto to backup all the blackboards of the tree. More...
 
void BlackboardClone (const Blackboard &src, Blackboard &dst)
 BlackboardClone make a copy of the content of the blackboard. More...
 
void BlackboardRestore (const std::vector< Blackboard::Ptr > &backup, BT::Tree &tree)
 BlackboardRestore uses Blackboard::cloneInto to restore all the blackboards of the tree. More...
 
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)
 
Any convertFromJSON (StringView json_text, std::type_index type)
 convertFromJSON will parse a json string and use JsonExporter to convert its content to a given type. It will work only if the type was previously registered. May throw if it fails. More...
 
template<typename T >
convertFromJSON (StringView str)
 Same as the non template version, but with automatic casting. More...
 
template<>
Point3D convertFromString (StringView key)
 
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<>
int16_t convertFromString< int16_t > (StringView str)
 
template<>
int32_t convertFromString< int32_t > (StringView str)
 
template<>
int64_t convertFromString< int64_t > (StringView str)
 
template<>
int8_t convertFromString< int8_t > (StringView str)
 
template<>
NodeStatus convertFromString< NodeStatus > (StringView str)
 
template<>
NodeType convertFromString< NodeType > (StringView str)
 
template<>
PortDirection convertFromString< PortDirection > (StringView str)
 
template<>
SharedQueue< bool > convertFromString< SharedQueue< bool > > (StringView str)
 
template<>
SharedQueue< double > convertFromString< SharedQueue< double > > (StringView str)
 
template<>
SharedQueue< int > convertFromString< SharedQueue< int > > (StringView str)
 
template<>
SharedQueue< std::string > convertFromString< SharedQueue< std::string > > (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<>
std::vector< std::string > convertFromString< std::vector< std::string > > (StringView str)
 
template<>
uint16_t convertFromString< uint16_t > (StringView str)
 
template<>
uint32_t convertFromString< uint32_t > (StringView str)
 
template<>
uint64_t convertFromString< uint64_t > (StringView str)
 
template<>
uint8_t convertFromString< uint8_t > (StringView str)
 
Serialization::NodeStatus convertToFlatbuffers (BT::NodeStatus type)
 
Serialization::NodeType convertToFlatbuffers (BT::NodeType type)
 
Serialization::PortDirection convertToFlatbuffers (BT::PortDirection direction)
 
template<typename T >
ConvertWithBoundCheck (StringView str)
 
template<typename T , typename... Args>
NodeBuilder CreateBuilder (Args... args)
 
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 = AnyTypeAllowed>
std::pair< std::string, PortInfoCreatePort (PortDirection direction, StringView name, StringView description={})
 
std::array< char, 16 > CreateRandomUUID ()
 
std::string demangle (char const *name)
 
std::string demangle (const std::type_index &index)
 
std::string demangle (const std::type_info &info)
 
char const * demangle_alloc (char const *name) noexcept
 
void demangle_free (char const *name) noexcept
 
nlohmann::json ExportBlackboardToJSON (const Blackboard &blackboard)
 ExportBlackboardToJSON will create a JSON that contains the current values of the blackboard. Complex types must be registered with JsonExporter::get() More...
 
nlohmann::json ExportTreeToJSON (const BT::Tree &tree)
 ExportTreeToJSON it calls ExportBlackboardToJSON for all the blackboards in the tree. More...
 
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 ()
 
template<typename T , typename... ExtraArgs>
constexpr bool hasNodeFullCtor ()
 
template<typename T >
constexpr bool hasNodeNameCtor ()
 
void ImportBlackboardFromJSON (const nlohmann::json &json, Blackboard &blackboard)
 ImportBlackboardFromJSON will append elements to the blackboard, using the values parsed from the JSON file created using ExportBlackboardToJSON. Complex types must be registered with JsonExporter::get() More...
 
void ImportTreeFromJSON (const nlohmann::json &json, BT::Tree &tree)
 ImportTreeFromJSON it calls ImportBlackboardFromJSON for all the blackboards in the tree. More...
 
template<typename T = AnyTypeAllowed, typename DefaultT = T>
std::pair< std::string, PortInfoInputPort (StringView name, const DefaultT &default_value, StringView description)
 
template<typename T = AnyTypeAllowed>
std::pair< std::string, PortInfoInputPort (StringView name, StringView description={})
 
bool IsAllowedPortName (StringView str)
 
template<typename T >
bool isCastingSafe (const std::type_index &type, const T &val)
 
template<typename T >
constexpr bool IsConvertibleToString ()
 
bool IsPrivateKey (StringView str)
 
bool isStatusActive (const NodeStatus &status)
 
bool isStatusCompleted (const NodeStatus &status)
 
int LibraryVersionNumber ()
 
const char * LibraryVersionString ()
 
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 = AnyTypeAllowed>
std::pair< std::string, PortInfoOutputPort (StringView name, StringView default_value, StringView description)
 
template<typename T = AnyTypeAllowed>
std::pair< std::string, PortInfoOutputPort (StringView name, StringView description={})
 
Expected< ScriptFunctionParseScript (const std::string &script)
 
Expected< AnyParseScriptAndExecute (Ast::Environment &env, const std::string &script)
 
void printTreeRecursively (const TreeNode *root_node, std::ostream &stream=std::cout)
 
template<typename T >
void RegisterJsonDefinition ()
 
SerializedTransition SerializeTransition (uint16_t UID, Duration timestamp, NodeStatus prev_status, NodeStatus status)
 
std::vector< StringViewsplitString (const StringView &strToSplit, char delimeter)
 
bool StartWith (StringView str, char prefix)
 
bool StartWith (StringView str, StringView prefix)
 
void StrAppend (std::string *destination, const std::string_view &a)
 
void StrAppend (std::string *destination, const std::string_view &a, const std::string_view &b)
 
void StrAppend (std::string *destination, const std::string_view &a, const std::string_view &b, const std::string_view &c)
 
template<typename... AV>
void StrAppend (std::string *destination, const std::string_view &a, const std::string_view &b, const std::string_view &c, const std::string_view &d, const AV &... args)
 
std::string StrCat ()
 
std::string StrCat (const std::string_view &a)
 
std::string StrCat (const std::string_view &a, const std::string_view &b)
 
std::string StrCat (const std::string_view &a, const std::string_view &b, const std::string_view &c)
 
template<typename... AV>
std::string StrCat (const std::string_view &a, const std::string_view &b, const std::string_view &c, const std::string_view &d, const AV &... args)
 
const char * toConstStr (NodeType type)
 
Expected< std::string > toJsonString (const Any &value)
 
std::string toStr (BT::NodeStatus status, bool colored)
 toStr converts NodeStatus to string. Optionally colored. More...
 
template<typename T >
std::string toStr (const T &value)
 toStr is the reverse operation of convertFromString. More...
 
template<>
std::string toStr< bool > (const bool &value)
 
template<>
std::string toStr< BT::NodeStatus > (const BT::NodeStatus &status)
 
template<>
std::string toStr< BT::NodeType > (const BT::NodeType &type)
 
template<>
std::string toStr< BT::PortDirection > (const BT::PortDirection &direction)
 
template<>
std::string toStr< BT::PostCond > (const BT::PostCond &status)
 
template<>
std::string toStr< BT::PreCond > (const BT::PreCond &status)
 
template<>
std::string toStr< NodeStatus > (const NodeStatus &status)
 
template<>
std::string toStr< NodeType > (const NodeType &type)
 
template<>
std::string toStr< PortDirection > (const PortDirection &direction)
 
template<>
std::string toStr< PostCond > (const PostCond &pre)
 
template<>
std::string toStr< PreCond > (const PreCond &pre)
 
template<>
std::string toStr< std::string > (const std::string &value)
 
int64_t ToUsec (Duration ts)
 
Result ValidateScript (const std::string &script)
 ValidateScript will check if a certain string is valid. More...
 
template<typename SRC , typename TO >
bool ValidCast (const SRC &val)
 
void VerifyXML (const std::string &xml_text, const std::unordered_map< std::string, BT::NodeType > &registered_nodes)
 
void VerifyXML (const std::string &xml_text, const std::unordered_map< std::string, NodeType > &registered_nodes)
 
bool WildcardMatch (const std::string &str, StringView filter)
 
std::string writeTreeNodesModelXML (const BehaviorTreeFactory &factory, bool include_builtin=false)
 writeTreeNodesModelXML generates an XMl that contains the manifests in the <TreeNodesModel> More...
 
std::string WriteTreeToXML (const Tree &tree, bool add_metadata, bool add_builtin_models)
 WriteTreeToXML create a string that contains the XML that corresponds to a given tree. When using this function with a logger, you should probably set both add_metadata and add_builtin_models to true. More...
 
std::string writeTreeXSD (const BehaviorTreeFactory &factory)
 writeTreeXSD generates an XSD for the nodes defined in the factory More...
 

Variables

constexpr const char * PLUGIN_SYMBOL = "BT_RegisterNodesFromPlugin"
 
auto StrEqual
 
static std::type_index UndefinedAnyType = typeid(nullptr)
 

Detailed Description

Template Action used in ex04_waypoints.cpp example.

Its purpose is to do make it easy to create while loops wich consume the elements of a queue.

Note that modifying the queue is not thread safe, therefore the action that creates the queue or push elements into it, must be Synchronous.

When ticked, we pop_front from the "queue" and insert that value in "popped_item". Return FAILURE if the queue is empty, SUCCESS otherwise.

Typedef Documentation

◆ AnyPtrLocked

using BT::AnyPtrLocked = typedef LockedPtr<Any>

This type contains a pointer to Any, protected with a locked mutex as long as the object is in scope

Definition at line 19 of file blackboard.h.

◆ Duration

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

Definition at line 628 of file basic_types.h.

◆ enable_if

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

Definition at line 305 of file basic_types.h.

◆ enable_if_not

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

Definition at line 308 of file basic_types.h.

◆ EnumsTable

using BT::EnumsTable = typedef std::unordered_map<std::string, int>

Simple map (string->nt), used to convert enums in the scripting language

Definition at line 22 of file script_parser.hpp.

◆ EnumsTablePtr

using BT::EnumsTablePtr = typedef std::shared_ptr<EnumsTable>

Definition at line 23 of file script_parser.hpp.

◆ ErrorReport

using BT::ErrorReport = typedef lexy_ext::_report_error<char*>

Definition at line 12 of file script_parser.cpp.

◆ Expected

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

Usage: given a function/method like this:

Expected<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 85 of file basic_types.h.

◆ KeyValueVector

using BT::KeyValueVector = typedef std::vector<std::pair<std::string, std::string> >

Definition at line 66 of file basic_types.h.

◆ NodeBuilder

using BT::NodeBuilder = typedef std::function<std::unique_ptr<TreeNode>(const std::string&, const NodeConfig&)>

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

Definition at line 31 of file bt_factory.h.

◆ NodeConfiguration

Definition at line 102 of file tree_node.h.

◆ PortsList

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

Definition at line 585 of file basic_types.h.

◆ PortsRemapping

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

Definition at line 43 of file tree_node.h.

◆ Result

using BT::Result = typedef Expected<std::monostate>

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 333 of file basic_types.h.

◆ ScriptFunction

using BT::ScriptFunction = typedef std::function<Any(Ast::Environment& env)>

Definition at line 43 of file script_parser.hpp.

◆ ScriptingEnumsRegistry

using BT::ScriptingEnumsRegistry = typedef std::unordered_map<std::string, int>

Definition at line 71 of file tree_node.h.

◆ SerializedTransition

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

Definition at line 9 of file bt_flatbuffer_helper.h.

◆ SerializedTreeStatus

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

Definition at line 72 of file behavior_tree.h.

◆ SharedQueue

template<typename T >
using BT::SharedQueue = typedef std::shared_ptr<std::deque<T> >

Definition at line 24 of file loop_node.h.

◆ StringConverter

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

Definition at line 206 of file basic_types.h.

◆ StringConvertersMap

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

Definition at line 208 of file basic_types.h.

◆ StringView

using BT::StringView = typedef std::string_view

Definition at line 59 of file basic_types.h.

◆ TimePoint

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

Definition at line 627 of file basic_types.h.

Enumeration Type Documentation

◆ anonymous enum

anonymous enum
Enumerator
IDLE_FROM_SUCCESS 
IDLE_FROM_FAILURE 
IDLE_FROM_RUNNING 

Definition at line 13 of file groot2_publisher.cpp.

◆ NodeStatus

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 
SKIPPED 

Definition at line 33 of file basic_types.h.

◆ NodeType

enum BT::NodeType
strong

Enumerates the possible types of nodes.

Enumerator
UNDEFINED 
ACTION 
CONDITION 
CONTROL 
DECORATOR 
SUBTREE 

Definition at line 20 of file basic_types.h.

◆ PortDirection

enum BT::PortDirection
strong
Enumerator
INPUT 
OUTPUT 
INOUT 

Definition at line 52 of file basic_types.h.

◆ PostCond

enum BT::PostCond
strong
Enumerator
ON_HALTED 
ON_FAILURE 
ON_SUCCESS 
ALWAYS 
COUNT_ 

Definition at line 55 of file tree_node.h.

◆ PreCond

enum BT::PreCond
strong
Enumerator
FAILURE_IF 
SUCCESS_IF 
SKIP_IF 
WHILE_TRUE 
COUNT_ 

Definition at line 45 of file tree_node.h.

◆ TimestampType

enum BT::TimestampType
strong
Enumerator
absolute 
relative 

Definition at line 9 of file abstract_logger.h.

Function Documentation

◆ addNodeModelToXML()

void BT::addNodeModelToXML ( const TreeNodeManifest model,
XMLDocument doc,
XMLElement model_root 
)

Definition at line 1026 of file xml_parsing.cpp.

◆ addTreeToXML()

void BT::addTreeToXML ( const Tree tree,
XMLDocument doc,
XMLElement rootXML,
bool  add_metadata,
bool  add_builtin_models 
)

Definition at line 1082 of file xml_parsing.cpp.

◆ applyRecursiveVisitor() [1/2]

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

Definition at line 18 of file behavior_tree.cpp.

◆ applyRecursiveVisitor() [2/2]

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

Definition at line 41 of file behavior_tree.cpp.

◆ assignDefaultRemapping()

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

Definition at line 603 of file tree_node.h.

◆ BidirectionalPort() [1/2]

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

Syntactic sugar to invoke CreatePort<T>(PortDirection::INOUT,...) It also sets the PortInfo::defaultValue()

Parameters
namethe name of the port
default_valuedefault value of the port, either type T of BlackboardKey
descriptionoptional human-readable description

Definition at line 555 of file basic_types.h.

◆ BidirectionalPort() [2/2]

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

Syntactic sugar to invoke CreatePort<T>(PortDirection::INOUT,...)

Parameters
namethe name of the port
descriptionoptional human-readable description

Definition at line 494 of file basic_types.h.

◆ BlackboardBackup()

std::vector< Blackboard::Ptr > BT::BlackboardBackup ( const BT::Tree tree)

BlackboardBackup uses Blackboard::cloneInto to backup all the blackboards of the tree.

Parameters
treesource
Returns
destination (the backup)

Definition at line 688 of file bt_factory.cpp.

◆ BlackboardClone()

void BT::BlackboardClone ( const Blackboard src,
Blackboard dst 
)

BlackboardClone make a copy of the content of the blackboard.

Parameters
srcsource
dstdestination

◆ BlackboardRestore()

void BT::BlackboardRestore ( const std::vector< Blackboard::Ptr > &  backup,
BT::Tree tree 
)

BlackboardRestore uses Blackboard::cloneInto to restore all the blackboards of the tree.

Parameters
backupa vectror of blackboards
treethe destination

Definition at line 679 of file bt_factory.cpp.

◆ buildSerializedStatusSnapshot() [1/2]

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.

◆ buildSerializedStatusSnapshot() [2/2]

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

Definition at line 101 of file behavior_tree.cpp.

◆ buildTreeFromFile()

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

Definition at line 1489 of file xml_parsing.cpp.

◆ buildTreeFromText()

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

Definition at line 1481 of file xml_parsing.cpp.

◆ convertFromJSON() [1/2]

Any BT::convertFromJSON ( StringView  json_text,
std::type_index  type 
)

convertFromJSON will parse a json string and use JsonExporter to convert its content to a given type. It will work only if the type was previously registered. May throw if it fails.

Parameters
json_texta valid JSON string
typeyou must specify the typeid()
Returns
the object, wrapped in Any.

Definition at line 443 of file basic_types.cpp.

◆ convertFromJSON() [2/2]

template<typename T >
T BT::convertFromJSON ( StringView  str)
inline

Same as the non template version, but with automatic casting.

Definition at line 104 of file basic_types.h.

◆ convertFromString()

template<>
Point2D BT::convertFromString< Point2D > ( StringView  str)
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.

If the string starts with the prefix "json:", it will fall back to convertFromJSON()

Definition at line 32 of file ex01_wrap_legacy.cpp.

◆ convertFromString< bool >()

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

Definition at line 253 of file basic_types.cpp.

◆ convertFromString< const char * >()

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

◆ convertFromString< double >()

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

Definition at line 191 of file basic_types.cpp.

◆ convertFromString< float >()

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

Definition at line 204 of file basic_types.cpp.

◆ convertFromString< int16_t >()

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

Definition at line 161 of file basic_types.cpp.

◆ convertFromString< int32_t >()

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

Definition at line 167 of file basic_types.cpp.

◆ convertFromString< int64_t >()

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

Definition at line 119 of file basic_types.cpp.

◆ convertFromString< int8_t >()

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

Definition at line 155 of file basic_types.cpp.

◆ convertFromString< NodeStatus >()

Definition at line 284 of file basic_types.cpp.

◆ convertFromString< NodeType >()

Definition at line 302 of file basic_types.cpp.

◆ convertFromString< PortDirection >()

Definition at line 318 of file basic_types.cpp.

◆ convertFromString< SharedQueue< bool > >()

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

Definition at line 137 of file loop_node.h.

◆ convertFromString< SharedQueue< double > >()

template<>
SharedQueue<double> BT::convertFromString< SharedQueue< double > > ( StringView  str)
inline

Definition at line 149 of file loop_node.h.

◆ convertFromString< SharedQueue< int > >()

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

Definition at line 125 of file loop_node.h.

◆ convertFromString< SharedQueue< std::string > >()

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

Definition at line 162 of file loop_node.h.

◆ convertFromString< std::string >()

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

Definition at line 113 of file basic_types.cpp.

◆ convertFromString< std::vector< double > >()

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

Definition at line 227 of file basic_types.cpp.

◆ convertFromString< std::vector< int > >()

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

Definition at line 214 of file basic_types.cpp.

◆ convertFromString< std::vector< std::string > >()

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

Definition at line 240 of file basic_types.cpp.

◆ convertFromString< uint16_t >()

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

Definition at line 179 of file basic_types.cpp.

◆ convertFromString< uint32_t >()

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

Definition at line 185 of file basic_types.cpp.

◆ convertFromString< uint64_t >()

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

Definition at line 131 of file basic_types.cpp.

◆ convertFromString< uint8_t >()

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

Definition at line 173 of file basic_types.cpp.

◆ convertToFlatbuffers() [1/3]

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

Definition at line 31 of file bt_flatbuffer_helper.h.

◆ convertToFlatbuffers() [2/3]

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

Definition at line 11 of file bt_flatbuffer_helper.h.

◆ convertToFlatbuffers() [3/3]

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

Definition at line 48 of file bt_flatbuffer_helper.h.

◆ ConvertWithBoundCheck()

template<typename T >
T BT::ConvertWithBoundCheck ( StringView  str)

Definition at line 143 of file basic_types.cpp.

◆ CreateBuilder()

template<typename T , typename... Args>
NodeBuilder BT::CreateBuilder ( Args...  args)
inline

Definition at line 34 of file bt_factory.h.

◆ CreateFlatbuffersBehaviorTree()

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

Definition at line 62 of file bt_flatbuffer_helper.h.

◆ CreateManifest()

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

Definition at line 42 of file bt_factory.h.

◆ CreatePort()

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

Definition at line 433 of file basic_types.h.

◆ CreateRandomUUID()

std::array<char, 16> BT::CreateRandomUUID ( )

Definition at line 33 of file groot2_publisher.cpp.

◆ demangle() [1/3]

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

Definition at line 74 of file demangle_util.h.

◆ demangle() [2/3]

std::string BT::demangle ( const std::type_index &  index)
inline

Definition at line 81 of file demangle_util.h.

◆ demangle() [3/3]

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

Definition at line 116 of file demangle_util.h.

◆ demangle_alloc()

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

Definition at line 66 of file demangle_util.h.

◆ demangle_free()

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

Definition at line 71 of file demangle_util.h.

◆ ExportBlackboardToJSON()

nlohmann::json BT::ExportBlackboardToJSON ( const Blackboard blackboard)

ExportBlackboardToJSON will create a JSON that contains the current values of the blackboard. Complex types must be registered with JsonExporter::get()

Definition at line 263 of file blackboard.cpp.

◆ ExportTreeToJSON()

nlohmann::json BT::ExportTreeToJSON ( const BT::Tree tree)

ExportTreeToJSON it calls ExportBlackboardToJSON for all the blackboards in the tree.

Definition at line 700 of file bt_factory.cpp.

◆ GetAnyFromStringFunctor()

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

Definition at line 212 of file basic_types.h.

◆ GetAnyFromStringFunctor< void >()

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

Definition at line 229 of file basic_types.h.

◆ getProvidedPorts() [1/2]

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

Definition at line 615 of file basic_types.h.

◆ getProvidedPorts() [2/2]

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

Definition at line 622 of file basic_types.h.

◆ getType()

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 88 of file behavior_tree.h.

◆ hasNodeFullCtor()

template<typename T , typename... ExtraArgs>
constexpr bool BT::hasNodeFullCtor ( )
inlineconstexpr

Definition at line 111 of file tree_node.h.

◆ hasNodeNameCtor()

template<typename T >
constexpr bool BT::hasNodeNameCtor ( )
inlineconstexpr

Definition at line 105 of file tree_node.h.

◆ ImportBlackboardFromJSON()

void BT::ImportBlackboardFromJSON ( const nlohmann::json json,
Blackboard blackboard 
)

ImportBlackboardFromJSON will append elements to the blackboard, using the values parsed from the JSON file created using ExportBlackboardToJSON. Complex types must be registered with JsonExporter::get()

Definition at line 280 of file blackboard.cpp.

◆ ImportTreeFromJSON()

void BT::ImportTreeFromJSON ( const nlohmann::json json,
BT::Tree tree 
)

ImportTreeFromJSON it calls ImportBlackboardFromJSON for all the blackboards in the tree.

Definition at line 716 of file bt_factory.cpp.

◆ InputPort() [1/2]

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

Syntactic sugar to invoke CreatePort<T>(PortDirection::INPUT,...) It also sets the PortInfo::defaultValue()

Parameters
namethe name of the port
default_valuedefault value of the port, either type T of BlackboardKey
descriptionoptional human-readable description

Definition at line 540 of file basic_types.h.

◆ InputPort() [2/2]

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

Syntactic sugar to invoke CreatePort<T>(PortDirection::INPUT, ...)

Parameters
namethe name of the port
descriptionoptional human-readable description

Definition at line 470 of file basic_types.h.

◆ IsAllowedPortName()

bool BT::IsAllowedPortName ( StringView  str)

Definition at line 421 of file basic_types.cpp.

◆ isCastingSafe()

template<typename T >
bool BT::isCastingSafe ( const std::type_index &  type,
const T &  val 
)
inline

Definition at line 252 of file safe_any.hpp.

◆ IsConvertibleToString()

template<typename T >
constexpr bool BT::IsConvertibleToString ( )
constexpr

Definition at line 237 of file basic_types.h.

◆ IsPrivateKey()

bool BT::IsPrivateKey ( StringView  str)

Definition at line 8 of file blackboard.cpp.

◆ isStatusActive()

bool BT::isStatusActive ( const NodeStatus status)
inline

Definition at line 42 of file basic_types.h.

◆ isStatusCompleted()

bool BT::isStatusCompleted ( const NodeStatus status)
inline

Definition at line 47 of file basic_types.h.

◆ LibraryVersionNumber()

int BT::LibraryVersionNumber ( )

Definition at line 114 of file behavior_tree.cpp.

◆ LibraryVersionString()

const char * BT::LibraryVersionString ( )

Definition at line 126 of file behavior_tree.cpp.

◆ operator<<() [1/3]

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

Definition at line 336 of file basic_types.cpp.

◆ operator<<() [2/3]

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

Definition at line 330 of file basic_types.cpp.

◆ operator<<() [3/3]

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

Definition at line 342 of file basic_types.cpp.

◆ OutputPort() [1/2]

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

Syntactic sugar to invoke CreatePort<T>(PortDirection::OUTPUT,...) It also sets the PortInfo::defaultValue()

Parameters
namethe name of the port
default_valuedefault blackboard entry where the output is written
descriptionoptional human-readable description

Definition at line 569 of file basic_types.h.

◆ OutputPort() [2/2]

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

Syntactic sugar to invoke CreatePort<T>(PortDirection::OUTPUT,...)

Parameters
namethe name of the port
descriptionoptional human-readable description

Definition at line 482 of file basic_types.h.

◆ ParseScript()

Expected< ScriptFunction > BT::ParseScript ( const std::string &  script)

Definition at line 14 of file script_parser.cpp.

◆ ParseScriptAndExecute()

BT::Expected< Any > BT::ParseScriptAndExecute ( Ast::Environment env,
const std::string &  script 
)

Definition at line 57 of file script_parser.cpp.

◆ printTreeRecursively()

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 66 of file behavior_tree.cpp.

◆ RegisterJsonDefinition()

template<typename T >
void BT::RegisterJsonDefinition ( )
inline

Definition at line 182 of file json_export.h.

◆ SerializeTransition()

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 142 of file bt_flatbuffer_helper.h.

◆ splitString()

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

Definition at line 348 of file basic_types.cpp.

◆ StartWith() [1/2]

bool BT::StartWith ( StringView  str,
char  prefix 
)

Definition at line 470 of file basic_types.cpp.

◆ StartWith() [2/2]

bool BT::StartWith ( StringView  str,
StringView  prefix 
)

Definition at line 464 of file basic_types.cpp.

◆ StrAppend() [1/4]

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

Definition at line 79 of file strcat.hpp.

◆ StrAppend() [2/4]

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

Definition at line 84 of file strcat.hpp.

◆ StrAppend() [3/4]

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

Definition at line 90 of file strcat.hpp.

◆ StrAppend() [4/4]

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

Definition at line 98 of file strcat.hpp.

◆ StrCat() [1/5]

std::string BT::StrCat ( )
inline

Definition at line 46 of file strcat.hpp.

◆ StrCat() [2/5]

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

Definition at line 51 of file strcat.hpp.

◆ StrCat() [3/5]

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

Definition at line 56 of file strcat.hpp.

◆ StrCat() [4/5]

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

Definition at line 61 of file strcat.hpp.

◆ StrCat() [5/5]

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

Definition at line 69 of file strcat.hpp.

◆ toConstStr()

const char* BT::toConstStr ( NodeType  type)

Definition at line 24 of file bt_minitrace_logger.cpp.

◆ toJsonString()

Expected< std::string > BT::toJsonString ( const Any value)

Definition at line 454 of file basic_types.cpp.

◆ toStr() [1/2]

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

toStr converts NodeStatus to string. Optionally colored.

Definition at line 42 of file basic_types.cpp.

◆ toStr() [2/2]

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

toStr is the reverse operation of convertFromString.

If T is a custom type and there is no template specialization, it will try to fall back to toJsonString()

Definition at line 252 of file basic_types.h.

◆ toStr< bool >()

template<>
std::string BT::toStr< bool > ( const bool &  value)

Definition at line 31 of file basic_types.cpp.

◆ toStr< BT::NodeStatus >()

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

◆ toStr< BT::NodeType >()

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

◆ toStr< BT::PortDirection >()

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

◆ toStr< BT::PostCond >()

template<>
std::string BT::toStr< BT::PostCond > ( const BT::PostCond status)

◆ toStr< BT::PreCond >()

template<>
std::string BT::toStr< BT::PreCond > ( const BT::PreCond status)

◆ toStr< NodeStatus >()

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

Definition at line 12 of file basic_types.cpp.

◆ toStr< NodeType >()

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

Definition at line 93 of file basic_types.cpp.

◆ toStr< PortDirection >()

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

Definition at line 78 of file basic_types.cpp.

◆ toStr< PostCond >()

template<>
std::string BT::toStr< PostCond > ( const PostCond pre)

Definition at line 479 of file tree_node.cpp.

◆ toStr< PreCond >()

template<>
std::string BT::toStr< PreCond > ( const PreCond pre)

Definition at line 461 of file tree_node.cpp.

◆ toStr< std::string >()

template<>
std::string BT::toStr< std::string > ( const std::string &  value)

Definition at line 37 of file basic_types.cpp.

◆ ToUsec()

int64_t BT::ToUsec ( Duration  ts)

Definition at line 8 of file bt_file_logger_v2.cpp.

◆ ValidateScript()

Result BT::ValidateScript ( const std::string &  script)

ValidateScript will check if a certain string is valid.

Definition at line 70 of file script_parser.cpp.

◆ ValidCast()

template<typename SRC , typename TO >
bool BT::ValidCast ( const SRC &  val)
inline

Definition at line 246 of file safe_any.hpp.

◆ VerifyXML() [1/2]

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

Definition at line 337 of file xml_parsing.cpp.

◆ VerifyXML() [2/2]

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

◆ WildcardMatch()

bool BT::WildcardMatch ( const std::string &  str,
StringView  filter 
)

Definition at line 27 of file bt_factory.cpp.

◆ writeTreeNodesModelXML()

std::string BT::writeTreeNodesModelXML ( const BehaviorTreeFactory factory,
bool  include_builtin = false 
)

writeTreeNodesModelXML generates an XMl that contains the manifests in the <TreeNodesModel>

Parameters
factorythe factory with the registered types
include_builtinif true, include the builtin Nodes
Returns
string containing the XML.

Definition at line 1178 of file xml_parsing.cpp.

◆ WriteTreeToXML()

std::string BT::WriteTreeToXML ( const Tree tree,
bool  add_metadata,
bool  add_builtin_models 
)

WriteTreeToXML create a string that contains the XML that corresponds to a given tree. When using this function with a logger, you should probably set both add_metadata and add_builtin_models to true.

Parameters
treethe input tree
add_metadataif true, the attributes "_uid" and "_fullPath" will be added to the nodes
add_builtin_modelsif true, include the builtin Nodes into the <TreeNodesModel>
Returns
string containing the XML.

Definition at line 1497 of file xml_parsing.cpp.

◆ writeTreeXSD()

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

writeTreeXSD generates an XSD for the nodes defined in the factory

Parameters
factorythe factory with the registered types
Returns
string containing the XML.

Definition at line 1210 of file xml_parsing.cpp.

Variable Documentation

◆ PLUGIN_SYMBOL

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

Definition at line 83 of file bt_factory.h.

◆ StrEqual

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

Definition at line 79 of file xml_parsing.cpp.

◆ UndefinedAnyType

std::type_index BT::UndefinedAnyType = typeid(nullptr)
static

Definition at line 32 of file safe_any.hpp.



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