|
| 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...
|
| |
|
| 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 |
| |
|
| 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) |
| |
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.