Namespaces | |
| namespace | detail |
| namespace | details |
| namespace | optional_lite |
Classes | |
| class | ActionNodeBase |
| class | AlwaysFailure |
| class | AlwaysSuccess |
| class | AsyncActionNode |
| The AsyncActionNode a different thread where the action will be executed. More... | |
| class | AsyncActionTest |
| class | BehaviorTreeException |
| class | BehaviorTreeFactory |
| class | Blackboard |
| class | BlackboardImpl |
| class | BlackboardLocal |
| class | BlackboardPreconditionNode |
| class | ConditionNode |
| class | ConditionTestNode |
| class | ControlNode |
| class | CoroActionNode |
| The CoroActionNode class is an ideal candidate for asynchronous actions which need to communicate with a service provider using an asynch request/reply interface (being a notable example ActionLib in ROS, MoveIt clients or move_base clients). More... | |
| class | DecoratorNode |
| class | DecoratorSubtreeNode |
| class | FallbackNode |
| The FallbackNode is used to try different strategies, until one succeed. If any child returns RUNNING, previous children will be ticked again. More... | |
| class | FallbackStarNode |
| The FallbackStarNode is used to try different strategies, until one succeed. If any child returns RUNNING, previous children will NOT be ticked again. More... | |
| class | FileLogger |
| class | ForceFailureDecorator |
| class | ForceSuccessDecorator |
| struct | in_place_t |
| class | InverterNode |
| class | LeafNode |
| class | MinitraceLogger |
| class | ParallelNode |
| class | PublisherZMQ |
| class | RepeatNode |
| class | RetryNode |
| class | scoped_demangled_name |
| class | SequenceNode |
| The SequenceNode is used to execute a sequence of children. If any child returns RUNNING, previous children will be ticked again. More... | |
| class | SequenceStarNode |
| The SequenceStarNode is used to execute a sequence of children. If any child returns RUNNING, previous children are not ticked again. More... | |
| class | SetBlackboard |
| class | SharedLibrary |
| class | Signal |
| class | SimpleActionNode |
| The SimpleActionNode provides an easy to use ActionNode. 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 | 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 | SyncActionNode |
| The SyncActionNode is an helper derived class that explicitly forbids the status RUNNING and doesn't require an implementation of halt() More... | |
| class | SyncActionTest |
| class | TickEngine |
| class | TimeoutNode |
| class | TimerQueue |
| struct | Tree |
| class | TreeNode |
| struct | TreeNodeManifest |
| This information is used mostly by the XMLParser. More... | |
| class | XMLParser |
Typedefs | |
| typedef AsyncActionNode | ActionNode |
| typedef std::chrono::high_resolution_clock::duration | Duration |
| typedef std::function < std::unique_ptr< TreeNode > const std::string &, const NodeParameters &)> | NodeBuilder |
| The term "Builder" refers to the Builder Pattern (https://en.wikipedia.org/wiki/Builder_pattern) | |
| typedef std::unordered_map < std::string, std::string > | NodeParameters |
| typedef std::array< uint8_t, 12 > | SerializedTransition |
| typedef std::vector< std::pair < uint16_t, uint8_t > > | SerializedTreeStatus |
| typedef nonstd::string_view | StringView |
| typedef std::chrono::high_resolution_clock::time_point | TimePoint |
Enumerations | |
| enum | FailurePolicy { FAIL_ON_ONE, FAIL_ON_ALL } |
| enum | NodeStatus { IDLE = 0, RUNNING, SUCCESS, FAILURE } |
| enum | NodeType { UNDEFINED = 0, ACTION, CONDITION, CONTROL, DECORATOR, SUBTREE } |
| enum | SuccessPolicy { SUCCEED_ON_ONE, SUCCEED_ON_ALL } |
| enum | TimestampType { ABSOLUTE, 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) |
| void | assignBlackboardToEntireTree (TreeNode *root_node, const Blackboard::Ptr &bb) |
| void | buildSerializedStatusSnapshot (const TreeNode *root_node, SerializedTreeStatus &serialized_buffer) |
| buildSerializedStatusSnapshot can be used to create a serialize 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". | |
| void | buildSerializedStatusSnapshot (TreeNode *root_node, SerializedTreeStatus &serialized_buffer) |
| Tree | buildTreeFromFile (const BehaviorTreeFactory &factory, const std::string &filename, const Blackboard::Ptr &blackboard=Blackboard::Ptr()) |
| Tree | buildTreeFromText (const BehaviorTreeFactory &factory, const std::string &text, const Blackboard::Ptr &blackboard=Blackboard::Ptr()) |
| child_halted_ (false) | |
| template<> | |
| Point3D | convertFromString (const StringView &key) |
| template<typename T > | |
| T | convertFromString (const StringView &) |
| template<> | |
| bool | convertFromString< bool > (const StringView &str) |
| template<> | |
| const char * | convertFromString< const char * > (const StringView &str) |
| template<> | |
| double | convertFromString< double > (const StringView &str) |
| template<> | |
| int | convertFromString< int > (const StringView &str) |
| template<> | |
| NodeStatus | convertFromString< NodeStatus > (const StringView &str) |
| template<> | |
| NodeType | convertFromString< NodeType > (const StringView &str) |
| template<> | |
| std::string | convertFromString< std::string > (const StringView &str) |
| template<> | |
| std::vector< double > | convertFromString< std::vector< double > > (const StringView &str) |
| template<> | |
| std::vector< int > | convertFromString< std::vector< int > > (const StringView &str) |
| template<> | |
| unsigned | convertFromString< unsigned > (const StringView &str) |
| BT_Serialization::Type | convertToFlatbuffers (NodeType type) |
| BT_Serialization::Status | convertToFlatbuffers (NodeStatus type) |
| void | CreateFlatbuffersBehaviorTree (flatbuffers::FlatBufferBuilder &builder, BT::TreeNode *root_node) |
| current_child_idx_ (0) | |
| std::string | demangle (char const *name) |
| char const * | demangle_alloc (char const *name) noexcept |
| void | demangle_free (char const *name) noexcept |
| template<typename T > | |
| NodeType | getType () |
| static uint16_t | getUID () |
| void | haltAllActions (TreeNode *root_node) |
| template<class T > | |
| in_place_t | in_place (detail::in_place_type_tag< T >=detail::in_place_type_tag< T >()) |
| template<std::size_t I> | |
| in_place_t | in_place (detail::in_place_index_tag< I >=detail::in_place_index_tag< I >()) |
| template<std::size_t I> | |
| in_place_t | in_place_index (detail::in_place_index_tag< I >=detail::in_place_index_tag< I >()) |
| template<class T > | |
| in_place_t | in_place_type (detail::in_place_type_tag< T >=detail::in_place_type_tag< T >()) |
| max_attempts_ (NTries) | |
| msec_ (milliseconds) | |
| num_cycles_ (NTries) | |
| std::ostream & | operator<< (std::ostream &os, const BT::NodeStatus &status) |
| std::ostream & | operator<< (std::ostream &os, const BT::NodeType &type) |
| void | printTreeRecursively (const TreeNode *root_node) |
| read_parameter_from_blackboard_ (false) | |
| reset_on_failure_ (reset_on_failure) | |
| SerializedTransition | SerializeTransition (uint16_t UID, Duration timestamp, NodeStatus prev_status, NodeStatus status) |
| std::vector< StringView > | splitString (const StringView &strToSplit, char delimeter) |
| threshold_ (threshold) | |
| const char * | toStr (const BT::NodeStatus &status, bool colored=false) |
| toStr converts NodeStatus to string. Optionally colored. | |
| const char * | toStr (const BT::NodeType &type) |
| toStr converts NodeType to string. | |
| try_index_ (0) | |
| std::string | writeXML (const BehaviorTreeFactory &factory, const TreeNode *root_node, bool compact_representation=false) |
Variables | |
| const char | PLUGIN_SYMBOL [] = "BT_RegisterNodesFromPlugin" |
| typedef AsyncActionNode BT::ActionNode |
Definition at line 148 of file action_node.h.
| typedef std::chrono::high_resolution_clock::duration BT::Duration |
Definition at line 36 of file tree_node.h.
| typedef std::function<std::unique_ptr<TreeNode>const std::string&, const NodeParameters&)> BT::NodeBuilder |
The term "Builder" refers to the Builder Pattern (https://en.wikipedia.org/wiki/Builder_pattern)
Definition at line 30 of file bt_factory.h.
| typedef std::unordered_map<std::string, std::string> BT::NodeParameters |
Definition at line 33 of file tree_node.h.
| typedef std::array<uint8_t, 12> BT::SerializedTransition |
Definition at line 14 of file abstract_logger.h.
| typedef std::vector<std::pair<uint16_t, uint8_t> > BT::SerializedTreeStatus |
Definition at line 57 of file behavior_tree.h.
| typedef nonstd::string_view BT::StringView |
Definition at line 58 of file basic_types.h.
| typedef std::chrono::high_resolution_clock::time_point BT::TimePoint |
Definition at line 35 of file tree_node.h.
| enum BT::FailurePolicy |
Definition at line 41 of file basic_types.h.
| enum BT::NodeStatus |
Definition at line 28 of file basic_types.h.
| enum BT::NodeType |
Definition at line 16 of file basic_types.h.
| enum BT::SuccessPolicy |
Definition at line 52 of file basic_types.h.
| enum BT::TimestampType |
Definition at line 8 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 41 of file behavior_tree.cpp.
| void BT::assignBlackboardToEntireTree | ( | TreeNode * | root_node, |
| const Blackboard::Ptr & | bb | ||
| ) |
Definition at line 110 of file behavior_tree.cpp.
| void BT::buildSerializedStatusSnapshot | ( | const TreeNode * | root_node, |
| SerializedTreeStatus & | serialized_buffer | ||
| ) |
buildSerializedStatusSnapshot can be used to create a serialize 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 98 of file behavior_tree.cpp.
| Tree BT::buildTreeFromFile | ( | const BehaviorTreeFactory & | factory, |
| const std::string & | filename, | ||
| const Blackboard::Ptr & | blackboard = Blackboard::Ptr() |
||
| ) |
Helper function to do the most common steps all at once: 1) Create an instance of XMLParse and call loadFromFile. 2) Instantiate the entire tree. 3) Assign the given Blackboard
return: a pair containing the root node (first) and a vector with all the instantiated nodes (second).
Definition at line 513 of file xml_parsing.cpp.
| Tree BT::buildTreeFromText | ( | const BehaviorTreeFactory & | factory, |
| const std::string & | text, | ||
| const Blackboard::Ptr & | blackboard = Blackboard::Ptr() |
||
| ) |
Helper function to do the most common steps all at once: 1) Create an instance of XMLParse and call loadFromText. 2) Instantiate the entire tree. 3) Assign the given Blackboard
return: a pair containing the root node (first) and a vector with all the instantiated nodes (second).
Definition at line 501 of file xml_parsing.cpp.
| BT::child_halted_ | ( | false | ) |
| Pose2D BT::convertFromString | ( | const StringView & | key | ) |
Definition at line 45 of file t06_wrap_legacy.cpp.
| T BT::convertFromString | ( | const StringView & | ) | [inline] |
TreeNode::getParam requires convertFromString to be implemented for your specific type, unless you are try to read it from a blackboard.
Definition at line 64 of file basic_types.h.
| bool BT::convertFromString< bool > | ( | const StringView & | str | ) |
Definition at line 126 of file basic_types.cpp.
| const char * BT::convertFromString< const char * > | ( | const StringView & | str | ) |
Definition at line 74 of file basic_types.cpp.
| double BT::convertFromString< double > | ( | const StringView & | str | ) |
Definition at line 92 of file basic_types.cpp.
| int BT::convertFromString< int > | ( | const StringView & | str | ) |
Definition at line 80 of file basic_types.cpp.
| NodeStatus BT::convertFromString< NodeStatus > | ( | const StringView & | str | ) |
Definition at line 171 of file basic_types.cpp.
| NodeType BT::convertFromString< NodeType > | ( | const StringView & | str | ) |
Definition at line 185 of file basic_types.cpp.
| std::string BT::convertFromString< std::string > | ( | const StringView & | str | ) |
Definition at line 68 of file basic_types.cpp.
| std::vector< double > BT::convertFromString< std::vector< double > > | ( | const StringView & | str | ) |
Definition at line 112 of file basic_types.cpp.
| std::vector< int > BT::convertFromString< std::vector< int > > | ( | const StringView & | str | ) |
Definition at line 98 of file basic_types.cpp.
| unsigned BT::convertFromString< unsigned > | ( | const StringView & | str | ) |
Definition at line 86 of file basic_types.cpp.
| BT_Serialization::Type BT::convertToFlatbuffers | ( | NodeType | type | ) | [inline] |
Definition at line 9 of file bt_flatbuffer_helper.h.
| BT_Serialization::Status BT::convertToFlatbuffers | ( | NodeStatus | type | ) | [inline] |
Definition at line 29 of file bt_flatbuffer_helper.h.
| void BT::CreateFlatbuffersBehaviorTree | ( | flatbuffers::FlatBufferBuilder & | builder, |
| BT::TreeNode * | root_node | ||
| ) | [inline] |
Definition at line 45 of file bt_flatbuffer_helper.h.
| BT::current_child_idx_ | ( | 0 | ) |
Definition at line 19 of file fallback_star_node.cpp.
| std::string BT::demangle | ( | char const * | name | ) | [inline] |
Definition at line 92 of file demangle_util.h.
| char const * BT::demangle_alloc | ( | char const * | name | ) | [inline] |
Definition at line 83 of file demangle_util.h.
| void BT::demangle_free | ( | char const * | name | ) | [inline] |
Definition at line 88 of file demangle_util.h.
| NodeType BT::getType | ( | ) | [inline] |
Simple way to extract the type of a TreeNode at COMPILE TIME. Useful to avoid the cost of without dynamic_cast or the virtual method TreeNode::type().
Definition at line 73 of file behavior_tree.h.
| static uint16_t BT::getUID | ( | ) | [static] |
Definition at line 19 of file tree_node.cpp.
| void BT::haltAllActions | ( | TreeNode * | root_node | ) |
Definition at line 116 of file behavior_tree.cpp.
| in_place_t BT::in_place | ( | detail::in_place_type_tag< T > | = detail::in_place_type_tag<T>() | ) | [inline] |
Definition at line 302 of file optional.hpp.
| in_place_t BT::in_place | ( | detail::in_place_index_tag< I > | = detail::in_place_index_tag<I>() | ) | [inline] |
Definition at line 308 of file optional.hpp.
| in_place_t BT::in_place_index | ( | detail::in_place_index_tag< I > | = detail::in_place_index_tag<I>() | ) | [inline] |
Definition at line 320 of file optional.hpp.
| in_place_t BT::in_place_type | ( | detail::in_place_type_tag< T > | = detail::in_place_type_tag<T>() | ) | [inline] |
Definition at line 314 of file optional.hpp.
| BT::max_attempts_ | ( | NTries | ) |
| BT::msec_ | ( | milliseconds | ) |
| BT::num_cycles_ | ( | NTries | ) |
| std::ostream & BT::operator<< | ( | std::ostream & | os, |
| const BT::NodeStatus & | status | ||
| ) |
Definition at line 204 of file basic_types.cpp.
| std::ostream & BT::operator<< | ( | std::ostream & | os, |
| const BT::NodeType & | type | ||
| ) |
Definition at line 198 of file basic_types.cpp.
| void BT::printTreeRecursively | ( | const TreeNode * | root_node | ) |
Debug function to print on a stream
Definition at line 63 of file behavior_tree.cpp.
| BT::read_parameter_from_blackboard_ | ( | false | ) |
Definition at line 24 of file parallel_node.cpp.
| BT::reset_on_failure_ | ( | reset_on_failure | ) |
| 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 92 of file bt_flatbuffer_helper.h.
| std::vector< StringView > BT::splitString | ( | const StringView & | strToSplit, |
| char | delimeter | ||
| ) |
Definition at line 210 of file basic_types.cpp.
| BT::threshold_ | ( | threshold | ) |
| const char * BT::toStr | ( | const BT::NodeStatus & | status, |
| bool | colored = false |
||
| ) |
toStr converts NodeStatus to string. Optionally colored.
Definition at line 7 of file basic_types.cpp.
| const char * BT::toStr | ( | const BT::NodeType & | type | ) |
toStr converts NodeType to string.
Definition at line 48 of file basic_types.cpp.
| BT::try_index_ | ( | 0 | ) |
| std::string BT::writeXML | ( | const BehaviorTreeFactory & | factory, |
| const TreeNode * | root_node, | ||
| bool | compact_representation = false |
||
| ) |
Definition at line 524 of file xml_parsing.cpp.
| const char BT::PLUGIN_SYMBOL[] = "BT_RegisterNodesFromPlugin" |
Definition at line 40 of file bt_factory.h.