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 | 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 asynch 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 | 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 |
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 |
struct | ProtectedQueue |
class | PublisherZMQ |
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 | 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 prefered way to implement asynchronous Actions. It is actually easier to use correctly, when compared with AsyncAction. 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 | 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 | |
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, PortInfo > | PortsList |
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 *, StringConverter > | StringConvertersMap |
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, PortInfo > | BidirectionalPort (StringView name, StringView description={}) |
template<typename T = void> | |
std::pair< std::string, PortInfo > | BidirectionalPort (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 > | |
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, PortInfo > | CreatePort (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, PortInfo > | InputPort (StringView name, StringView description={}) |
template<typename T = void> | |
std::pair< std::string, PortInfo > | InputPort (StringView name, const T &default_value, StringView description) |
template<typename T > | |
bool | IsSame (const T &a, const T &b) |
bool | IsSame (const double &a, const double &b) |
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, PortInfo > | OutputPort (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< StringView > | splitString (const StringView &strToSplit, char delimeter) |
bool | StatusCompleted (const NodeStatus &status) |
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::unordered_map< std::string, NodeType > ®istered_nodes) |
void | VerifyXML (const std::string &xml_text, const std::unordered_map< std::string, BT::NodeType > ®istered_nodes) |
std::string | writeTreeNodesModelXML (const BehaviorTreeFactory &factory, bool include_builtin=false) |
Variables | |
constexpr const char * | PLUGIN_SYMBOL = "BT_RegisterNodesFromPlugin" |
const std::unordered_set< std::string > | ReservedPortNames = {"ID", "name", "_description"} |
auto | StrEqual |
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 std::chrono::high_resolution_clock::duration BT::Duration |
Definition at line 362 of file basic_types.h.
using BT::enable_if = typedef typename std::enable_if<Predicate::value>::type* |
Definition at line 175 of file basic_types.h.
using BT::enable_if_not = typedef typename std::enable_if<!Predicate::value>::type* |
Definition at line 178 of file basic_types.h.
using BT::has_default_constructor = typedef typename std::is_constructible<T, const std::string&> |
Definition at line 35 of file bt_factory.h.
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 32 of file bt_factory.h.
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 197 of file basic_types.h.
typedef std::unordered_map<std::string, PortInfo> BT::PortsList |
Definition at line 333 of file basic_types.h.
typedef std::unordered_map<std::string, std::string> BT::PortsRemapping |
Definition at line 42 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 217 of file basic_types.h.
typedef std::array< uint8_t, 12 > BT::SerializedTransition |
Definition at line 9 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 121 of file basic_types.h.
typedef std::unordered_map<const std::type_info*, StringConverter> BT::StringConvertersMap |
Definition at line 123 of file basic_types.h.
typedef nonstd::string_view BT::StringView |
Definition at line 55 of file basic_types.h.
typedef std::chrono::high_resolution_clock::time_point BT::TimePoint |
Definition at line 361 of file basic_types.h.
|
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.
|
strong |
Enumerates the possible types of nodes.
Enumerator | |
---|---|
UNDEFINED | |
ACTION | |
CONDITION | |
CONTROL | |
DECORATOR | |
SUBTREE |
Definition at line 22 of file basic_types.h.
|
strong |
Enumerator | |
---|---|
INPUT | |
OUTPUT | |
INOUT |
Definition at line 48 of file basic_types.h.
|
strong |
Enumerator | |
---|---|
absolute | |
relative |
Definition at line 9 of file abstract_logger.h.
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 42 of file behavior_tree.cpp.
|
inline |
Definition at line 326 of file tree_node.h.
|
inline |
Definition at line 307 of file basic_types.h.
|
inline |
Definition at line 323 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".
root_node | |
serialized_buffer | is the output. |
void BT::buildSerializedStatusSnapshot | ( | TreeNode * | root_node, |
SerializedTreeStatus & | serialized_buffer | ||
) |
Definition at line 103 of file behavior_tree.cpp.
Tree BT::buildTreeFromFile | ( | const BehaviorTreeFactory & | factory, |
const std::string & | filename, | ||
const Blackboard::Ptr & | blackboard | ||
) |
Definition at line 898 of file xml_parsing.cpp.
Tree BT::buildTreeFromText | ( | const BehaviorTreeFactory & | factory, |
const std::string & | text, | ||
const Blackboard::Ptr & | blackboard | ||
) |
Definition at line 890 of file xml_parsing.cpp.
|
inline |
Definition at line 20 of file t03_generic_ports.cpp.
|
inline |
Definition at line 21 of file movebase_node.h.
Point3D BT::convertFromString | ( | StringView | key | ) |
Definition at line 32 of file ex01_wrap_legacy.cpp.
|
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 66 of file basic_types.h.
bool BT::convertFromString< bool > | ( | StringView | str | ) |
Definition at line 178 of file basic_types.cpp.
const char* BT::convertFromString< const char *> | ( | StringView | str | ) |
double BT::convertFromString< double > | ( | StringView | str | ) |
Definition at line 127 of file basic_types.cpp.
float BT::convertFromString< float > | ( | StringView | str | ) |
Definition at line 140 of file basic_types.cpp.
int BT::convertFromString< int > | ( | StringView | str | ) |
Definition at line 103 of file basic_types.cpp.
long BT::convertFromString< long > | ( | StringView | str | ) |
Definition at line 109 of file basic_types.cpp.
NodeStatus BT::convertFromString< NodeStatus > | ( | StringView | str | ) |
Definition at line 209 of file basic_types.cpp.
NodeType BT::convertFromString< NodeType > | ( | StringView | str | ) |
Definition at line 224 of file basic_types.cpp.
PortDirection BT::convertFromString< PortDirection > | ( | StringView | str | ) |
Definition at line 240 of file basic_types.cpp.
std::string BT::convertFromString< std::string > | ( | StringView | str | ) |
Definition at line 97 of file basic_types.cpp.
std::vector< double > BT::convertFromString< std::vector< double > > | ( | StringView | str | ) |
Definition at line 164 of file basic_types.cpp.
std::vector< int > BT::convertFromString< std::vector< int > > | ( | StringView | str | ) |
Definition at line 150 of file basic_types.cpp.
unsigned BT::convertFromString< unsigned > | ( | StringView | str | ) |
Definition at line 115 of file basic_types.cpp.
unsigned long BT::convertFromString< unsigned long > | ( | StringView | str | ) |
Definition at line 121 of file basic_types.cpp.
|
inline |
Definition at line 11 of file bt_flatbuffer_helper.h.
|
inline |
Definition at line 31 of file bt_flatbuffer_helper.h.
|
inline |
Definition at line 47 of file bt_flatbuffer_helper.h.
|
inline |
Definition at line 43 of file bt_factory.h.
|
inline |
Definition at line 59 of file bt_factory.h.
|
inline |
Definition at line 69 of file bt_factory.h.
|
inline |
Definition at line 61 of file bt_flatbuffer_helper.h.
|
inline |
Definition at line 78 of file bt_factory.h.
std::pair<std::string, PortInfo> BT::CreatePort | ( | PortDirection | direction, |
StringView | name, | ||
StringView | description = {} |
||
) |
Definition at line 265 of file basic_types.h.
|
inline |
Definition at line 72 of file demangle_util.h.
|
inline |
Definition at line 79 of file demangle_util.h.
|
inline |
Definition at line 101 of file demangle_util.h.
|
inlinenoexcept |
Definition at line 64 of file demangle_util.h.
|
inlinenoexcept |
Definition at line 69 of file demangle_util.h.
|
inline |
Definition at line 127 of file basic_types.h.
|
inline |
Definition at line 133 of file basic_types.h.
|
inline |
Definition at line 349 of file basic_types.h.
|
inline |
Definition at line 356 of file basic_types.h.
|
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 |
Definition at line 19 of file tree_node.cpp.
|
inline |
Definition at line 293 of file basic_types.h.
|
inline |
Definition at line 314 of file basic_types.h.
|
inline |
Definition at line 65 of file blackboard_precondition.h.
|
inline |
Definition at line 70 of file blackboard_precondition.h.
std::ostream & BT::operator<< | ( | std::ostream & | os, |
const BT::NodeStatus & | status | ||
) |
Definition at line 255 of file basic_types.cpp.
std::ostream & BT::operator<< | ( | std::ostream & | os, |
const BT::NodeType & | type | ||
) |
Definition at line 249 of file basic_types.cpp.
std::ostream & BT::operator<< | ( | std::ostream & | os, |
const BT::PortDirection & | type | ||
) |
Definition at line 261 of file basic_types.cpp.
|
inline |
Definition at line 300 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 68 of file behavior_tree.cpp.
|
inline |
Serialize manually the informations about state transition No flatbuffer serialization here
Definition at line 139 of file bt_flatbuffer_helper.h.
std::vector< StringView > BT::splitString | ( | const StringView & | strToSplit, |
char | delimeter | ||
) |
Definition at line 267 of file basic_types.cpp.
|
inline |
Definition at line 43 of file basic_types.h.
|
inline |
Definition at line 80 of file strcat.hpp.
|
inline |
Definition at line 86 of file strcat.hpp.
|
inline |
Definition at line 93 of file strcat.hpp.
|
inline |
Definition at line 103 of file strcat.hpp.
|
inline |
Definition at line 47 of file strcat.hpp.
|
inline |
Definition at line 49 of file strcat.hpp.
|
inline |
Definition at line 53 of file strcat.hpp.
|
inline |
Definition at line 59 of file strcat.hpp.
|
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.
std::string BT::toStr | ( | T | value | ) |
Definition at line 141 of file basic_types.h.
std::string BT::toStr | ( | std::string | value | ) |
Definition at line 25 of file basic_types.cpp.
std::string BT::toStr | ( | BT::NodeStatus | status, |
bool | colored | ||
) |
toStr converts NodeStatus to string. Optionally colored.
Definition at line 30 of file basic_types.cpp.
std::string BT::toStr< BT::NodeStatus > | ( | BT::NodeStatus | status | ) |
std::string BT::toStr< BT::NodeType > | ( | BT::NodeType | type | ) |
toStr converts NodeType to string.
std::string BT::toStr< BT::PortDirection > | ( | BT::PortDirection | direction | ) |
std::string BT::toStr< NodeStatus > | ( | NodeStatus | status | ) |
Definition at line 9 of file basic_types.cpp.
Definition at line 77 of file basic_types.cpp.
std::string BT::toStr< PortDirection > | ( | PortDirection | direction | ) |
Definition at line 62 of file basic_types.cpp.
void BT::VerifyXML | ( | const std::string & | xml_text, |
const std::unordered_map< std::string, NodeType > & | registered_nodes | ||
) |
void BT::VerifyXML | ( | const std::string & | xml_text, |
const std::unordered_map< std::string, BT::NodeType > & | registered_nodes | ||
) |
Definition at line 235 of file xml_parsing.cpp.
std::string BT::writeTreeNodesModelXML | ( | const BehaviorTreeFactory & | factory, |
bool | include_builtin = false |
||
) |
Definition at line 791 of file xml_parsing.cpp.
constexpr const char* BT::PLUGIN_SYMBOL = "BT_RegisterNodesFromPlugin" |
Definition at line 115 of file bt_factory.h.
const std::unordered_set<std::string> BT::ReservedPortNames = {"ID", "name", "_description"} |
Definition at line 219 of file basic_types.h.
auto BT::StrEqual |
Definition at line 45 of file xml_parsing.cpp.