bt_factory.h
Go to the documentation of this file.
1 /* Copyright (C) 2018 Michele Colledanchise - All Rights Reserved
2  * Copyright (C) 2018-2023 Davide Faconti - All Rights Reserved
3 *
4 * Permission is hereby granted, free of charge, to any person obtaining a copy of this software and associated documentation files (the "Software"),
5 * to deal in the Software without restriction, including without limitation the rights to use, copy, modify, merge, publish, distribute, sublicense,
6 * and/or sell copies of the Software, and to permit persons to whom the Software is furnished to do so, subject to the following conditions:
7 * The above copyright notice and this permission notice shall be included in all copies or substantial portions of the Software.
8 *
9 * THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY,
10 * FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER LIABILITY,
11 * WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE SOFTWARE.
12 */
13 
14 #ifndef BT_FACTORY_H
15 #define BT_FACTORY_H
16 
17 #include <filesystem>
18 #include <functional>
19 #include <memory>
20 #include <unordered_map>
21 #include <set>
22 #include <vector>
23 
26 
27 namespace BT
28 {
30 using NodeBuilder =
31  std::function<std::unique_ptr<TreeNode>(const std::string&, const NodeConfig&)>;
32 
33 template <typename T, typename... Args>
34 inline NodeBuilder CreateBuilder(Args... args)
35 {
36  return [=](const std::string& name, const NodeConfig& config) {
37  return TreeNode::Instantiate<T, Args...>(name, config, args...);
38  };
39 }
40 
41 template <typename T>
42 inline TreeNodeManifest CreateManifest(const std::string& ID,
43  PortsList portlist = getProvidedPorts<T>())
44 {
46  {
47  return { getType<T>(), ID, portlist, T::metadata() };
48  }
49  return { getType<T>(), ID, portlist, {} };
50 }
51 
52 #ifdef BT_PLUGIN_EXPORT
53 
54 #if defined(_WIN32)
55 #define BTCPP_EXPORT extern "C" __declspec(dllexport)
56 #else
57 // Unix-like OSes
58 #define BTCPP_EXPORT extern "C" __attribute__((visibility("default")))
59 #endif
60 
61 #else
62 #define BTCPP_EXPORT static
63 #endif
64 /* Use this macro to automatically register one or more custom Nodes
65 * into a factory. For instance:
66 *
67 * BT_REGISTER_NODES(factory)
68 * {
69 * factory.registerNodeType<MoveBaseAction>("MoveBase");
70 * }
71 *
72 * IMPORTANT: this function MUST be declared in a cpp file, NOT a header file.
73 * You must add the definition [BT_PLUGIN_EXPORT] in CMakeLists.txt using:
74 *
75 * target_compile_definitions(my_plugin_target PRIVATE BT_PLUGIN_EXPORT )
76 
77 * See examples in sample_nodes directory.
78 */
79 
80 #define BT_REGISTER_NODES(factory) \
81  BTCPP_EXPORT void BT_RegisterNodesFromPlugin(BT::BehaviorTreeFactory& factory)
82 
83 constexpr const char* PLUGIN_SYMBOL = "BT_RegisterNodesFromPlugin";
84 
85 bool WildcardMatch(const std::string& str, StringView filter);
86 
91 class Tree
92 {
93 public:
94  // a tree can contain multiple subtree.
95  struct Subtree
96  {
97  using Ptr = std::shared_ptr<Subtree>;
98  std::vector<TreeNode::Ptr> nodes;
100  std::string instance_name;
101  std::string tree_ID;
102  };
103 
104  std::vector<Subtree::Ptr> subtrees;
105  std::unordered_map<std::string, TreeNodeManifest> manifests;
106 
107  Tree();
108 
109  Tree(const Tree&) = delete;
110  Tree& operator=(const Tree&) = delete;
111 
112  Tree(Tree&& other);
113  Tree& operator=(Tree&& other);
114 
115  void initialize();
116 
117  void haltTree();
118 
119  [[nodiscard]] TreeNode* rootNode() const;
120 
128  bool sleep(std::chrono::system_clock::duration timeout);
129 
130  ~Tree();
131 
135 
142 
146  NodeStatus
147  tickWhileRunning(std::chrono::milliseconds sleep_time = std::chrono::milliseconds(10));
148 
149  [[nodiscard]] Blackboard::Ptr rootBlackboard();
150 
151  //Call the visitor for each node of the tree.
152  void applyVisitor(const std::function<void(const TreeNode*)>& visitor);
153 
154  //Call the visitor for each node of the tree.
155  void applyVisitor(const std::function<void(TreeNode*)>& visitor);
156 
157  [[nodiscard]] uint16_t getUID();
158 
164  template <typename NodeType = BT::TreeNode>
165  [[nodiscard]] std::vector<const TreeNode*>
166  getNodesByPath(StringView wildcard_filter) const
167  {
168  std::vector<const TreeNode*> nodes;
169  for(auto const& subtree : subtrees)
170  {
171  for(auto const& node : subtree->nodes)
172  {
173  if(auto node_recast = dynamic_cast<const NodeType*>(node.get()))
174  {
175  if(WildcardMatch(node->fullPath(), wildcard_filter))
176  {
177  nodes.push_back(node.get());
178  }
179  }
180  }
181  }
182  return nodes;
183  }
184 
185 private:
186  std::shared_ptr<WakeUpSignal> wake_up_;
187 
189  {
193  };
194 
195  NodeStatus tickRoot(TickOption opt, std::chrono::milliseconds sleep_time);
196 
197  uint16_t uid_counter_ = 0;
198 };
199 
200 class Parser;
201 
210 {
211 public:
214 
215  BehaviorTreeFactory(const BehaviorTreeFactory& other) = delete;
216  BehaviorTreeFactory& operator=(const BehaviorTreeFactory& other) = delete;
217 
218  BehaviorTreeFactory(BehaviorTreeFactory&& other) noexcept;
220 
222  bool unregisterBuilder(const std::string& ID);
223 
229  void registerBuilder(const TreeNodeManifest& manifest, const NodeBuilder& builder);
230 
231  template <typename T>
232  void registerBuilder(const std::string& ID, const NodeBuilder& builder)
233  {
234  auto manifest = CreateManifest<T>(ID);
235  registerBuilder(manifest, builder);
236  }
237 
246  void registerSimpleAction(const std::string& ID,
247  const SimpleActionNode::TickFunctor& tick_functor,
248  PortsList ports = {});
257  void registerSimpleCondition(const std::string& ID,
258  const SimpleConditionNode::TickFunctor& tick_functor,
259  PortsList ports = {});
268  void registerSimpleDecorator(const std::string& ID,
269  const SimpleDecoratorNode::TickFunctor& tick_functor,
270  PortsList ports = {});
271 
277  void registerFromPlugin(const std::string& file_path);
278 
284  void registerFromROSPlugins();
285 
296  void registerBehaviorTreeFromFile(const std::filesystem::path& filename);
297 
300  void registerBehaviorTreeFromText(const std::string& xml_text);
301 
304  [[nodiscard]] std::vector<std::string> registeredBehaviorTrees() const;
305 
310 
319  [[nodiscard]] std::unique_ptr<TreeNode> instantiateTreeNode(
320  const std::string& name, const std::string& ID, const NodeConfig& config) const;
321 
325  template <typename T, typename... ExtraArgs>
326  void registerNodeType(const std::string& ID, const PortsList& ports, ExtraArgs... args)
327  {
332  "[registerNode]: accepts only classed derived from either "
333  "ActionNodeBase, "
334  "DecoratorNode, ControlNode or ConditionNode");
335 
336  constexpr bool default_constructable =
338  constexpr bool param_constructable =
339  std::is_constructible<T, const std::string&, const NodeConfig&,
340  ExtraArgs...>::value;
341 
342  // clang-format off
343  static_assert(!std::is_abstract<T>::value,
344  "[registerNode]: Some methods are pure virtual. "
345  "Did you override the methods tick() and halt()?");
346 
347  static_assert(default_constructable || param_constructable,
348  "[registerNode]: the registered class must have at least one of these two constructors:\n"
349  " (const std::string&, const NodeConfig&) or (const std::string&)\n"
350  "Check also if the constructor is public!)");
351  // clang-format on
352 
353  registerBuilder(CreateManifest<T>(ID, ports), CreateBuilder<T>(args...));
354  }
355 
361  template <typename T, typename... ExtraArgs>
362  void registerNodeType(const std::string& ID, ExtraArgs... args)
363  {
364  if constexpr(std::is_abstract_v<T>)
365  {
366  // check first if the given class is abstract
367  static_assert(!std::is_abstract_v<T>, "The Node type can't be abstract. "
368  "Did you forget to implement an abstract "
369  "method in the derived class?");
370  }
371  else
372  {
373  constexpr bool param_constructable =
374  std::is_constructible<T, const std::string&, const NodeConfig&,
375  ExtraArgs...>::value;
376  constexpr bool has_static_ports_list = has_static_method_providedPorts<T>::value;
377 
378  // clang-format off
379  static_assert(!(param_constructable && !has_static_ports_list),
380  "[registerNode]: you MUST implement the static method:\n"
381  " PortsList providedPorts();\n");
382 
383  static_assert(!(has_static_ports_list && !param_constructable),
384  "[registerNode]: since you have a static method providedPorts(),\n"
385  "you MUST add a constructor with signature:\n"
386  "(const std::string&, const NodeConfig&)\n");
387  }
388  // clang-format on
389  registerNodeType<T>(ID, getProvidedPorts<T>(), args...);
390  }
391 
393  [[nodiscard]] const std::unordered_map<std::string, NodeBuilder>& builders() const;
394 
396  [[nodiscard]] const std::unordered_map<std::string, TreeNodeManifest>&
397  manifests() const;
398 
400  [[nodiscard]] const std::set<std::string>& builtinNodes() const;
401 
413  [[nodiscard]] Tree createTreeFromText(
414  const std::string& text, Blackboard::Ptr blackboard = Blackboard::create());
415 
427  [[nodiscard]] Tree
428  createTreeFromFile(const std::filesystem::path& file_path,
429  Blackboard::Ptr blackboard = Blackboard::create());
430 
431  [[nodiscard]] Tree createTree(const std::string& tree_name,
432  Blackboard::Ptr blackboard = Blackboard::create());
433 
436  void addMetadataToManifest(const std::string& node_id, const KeyValueVector& metadata);
437 
451  void registerScriptingEnum(StringView name, int value);
452 
461  template <typename EnumType>
463  {
464  constexpr auto entries = magic_enum::enum_entries<EnumType>();
465  for(const auto& it : entries)
466  {
467  registerScriptingEnum(it.second, static_cast<int>(it.first));
468  }
469  }
470 
471  void clearSubstitutionRules();
472 
473  using SubstitutionRule = std::variant<std::string, TestNodeConfig>;
474 
487 
495  void loadSubstitutionRuleFromJSON(const std::string& json_text);
496 
500  [[nodiscard]] const std::unordered_map<std::string, SubstitutionRule>&
501  substitutionRules() const;
502 
503 private:
504  struct PImpl;
505  std::unique_ptr<PImpl> _p;
506 };
507 
514 void BlackboardClone(const Blackboard& src, Blackboard& dst);
515 
523 std::vector<Blackboard::Ptr> BlackboardBackup(const BT::Tree& tree);
524 
532 void BlackboardRestore(const std::vector<Blackboard::Ptr>& backup, BT::Tree& tree);
533 
539 
544 void ImportTreeFromJSON(const nlohmann::json& json, BT::Tree& tree);
545 
546 } // namespace BT
547 
548 #endif // BT_FACTORY_H
BT
Definition: ex01_wrap_legacy.cpp:29
BT::BehaviorTreeFactory::builtinNodes
const std::set< std::string > & builtinNodes() const
List of builtin IDs.
Definition: bt_factory.cpp:390
BT::BlackboardRestore
void BlackboardRestore(const std::vector< Blackboard::Ptr > &backup, BT::Tree &tree)
BlackboardRestore uses Blackboard::cloneInto to restore all the blackboards of the tree.
Definition: bt_factory.cpp:680
BT::NodeType
NodeType
Enumerates the possible types of nodes.
Definition: basic_types.h:20
BT::Tree::ONCE_UNLESS_WOKEN_UP
@ ONCE_UNLESS_WOKEN_UP
Definition: bt_factory.h:191
BT::Tree::getUID
uint16_t getUID()
Definition: bt_factory.cpp:634
BT::BehaviorTreeFactory::registeredBehaviorTrees
std::vector< std::string > registeredBehaviorTrees() const
Definition: bt_factory.cpp:282
BT::BehaviorTreeFactory::createTree
Tree createTree(const std::string &tree_name, Blackboard::Ptr blackboard=Blackboard::create())
Definition: bt_factory.cpp:432
BT::CreateBuilder
NodeBuilder CreateBuilder(Args... args)
Definition: bt_factory.h:34
BT::BehaviorTreeFactory::unregisterBuilder
bool unregisterBuilder(const std::string &ID)
Remove a registered ID.
Definition: bt_factory.cpp:124
BT::BehaviorTreeFactory::registerBuilder
void registerBuilder(const std::string &ID, const NodeBuilder &builder)
Definition: bt_factory.h:232
BT::SimpleDecoratorNode::TickFunctor
std::function< NodeStatus(NodeStatus, TreeNode &)> TickFunctor
Definition: decorator_node.h:55
magic_enum.hpp
BT::Tree::operator=
Tree & operator=(const Tree &)=delete
BT::BehaviorTreeFactory::operator=
BehaviorTreeFactory & operator=(const BehaviorTreeFactory &other)=delete
BT::Tree::Subtree::nodes
std::vector< TreeNode::Ptr > nodes
Definition: bt_factory.h:98
BT::BehaviorTreeFactory::substitutionRules
const std::unordered_map< std::string, SubstitutionRule > & substitutionRules() const
substitutionRules return the current substitution rules.
Definition: bt_factory.cpp:529
BT::BehaviorTreeFactory::_p
std::unique_ptr< PImpl > _p
Definition: bt_factory.h:504
BT::BehaviorTreeFactory::BehaviorTreeFactory
BehaviorTreeFactory()
Definition: bt_factory.cpp:43
BT::StringView
std::string_view StringView
Definition: basic_types.h:59
BT::BehaviorTreeFactory::loadSubstitutionRuleFromJSON
void loadSubstitutionRuleFromJSON(const std::string &json_text)
loadSubstitutionRuleFromJSON will parse a JSON file to create a set of substitution rules....
Definition: bt_factory.cpp:480
BT::BehaviorTreeFactory::registerFromPlugin
void registerFromPlugin(const std::string &file_path)
registerFromPlugin load a shared library and execute the function BT_REGISTER_NODES (see macro).
Definition: bt_factory.cpp:192
BT::TreeNode
Abstract base class for Behavior Tree Nodes.
Definition: tree_node.h:118
BT::Tree
Struct used to store a tree. If this object goes out of scope, the tree is destroyed.
Definition: bt_factory.h:91
BT::Tree::manifests
std::unordered_map< std::string, TreeNodeManifest > manifests
Definition: bt_factory.h:105
BT::BehaviorTreeFactory::addMetadataToManifest
void addMetadataToManifest(const std::string &node_id, const KeyValueVector &metadata)
Definition: bt_factory.cpp:440
BT::Tree::tickOnce
NodeStatus tickOnce()
by default, tickOnce() sends a single tick, BUT as long as there is at least one node of the tree inv...
Definition: bt_factory.cpp:605
manifest
string manifest
BT::Tree::Subtree
Definition: bt_factory.h:95
basic_json
namespace for Niels Lohmann
Definition: json.hpp:3411
BT::PLUGIN_SYMBOL
constexpr const char * PLUGIN_SYMBOL
Definition: bt_factory.h:83
BT::BehaviorTreeFactory::clearRegisteredBehaviorTrees
void clearRegisteredBehaviorTrees()
Clear previously-registered behavior trees.
Definition: bt_factory.cpp:287
BT::Tree::Tree
Tree()
Definition: bt_factory.cpp:542
magic_enum::detail::value
constexpr E value(std::size_t i) noexcept
Definition: magic_enum.hpp:664
BT::BehaviorTreeFactory::clearSubstitutionRules
void clearSubstitutionRules()
Definition: bt_factory.cpp:470
BT::BehaviorTreeFactory::registerScriptingEnum
void registerScriptingEnum(StringView name, int value)
Add an Enum to the scripting language. For instance if you do:
Definition: bt_factory.cpp:451
BT::BehaviorTreeFactory::manifests
const std::unordered_map< std::string, TreeNodeManifest > & manifests() const
Manifests of all the registered TreeNodes.
Definition: bt_factory.cpp:385
BT::WildcardMatch
bool WildcardMatch(const std::string &str, StringView filter)
Definition: bt_factory.cpp:27
BT::Tree::Subtree::Ptr
std::shared_ptr< Subtree > Ptr
Definition: bt_factory.h:97
BT::BehaviorTreeFactory::instantiateTreeNode
std::unique_ptr< TreeNode > instantiateTreeNode(const std::string &name, const std::string &ID, const NodeConfig &config) const
instantiateTreeNode creates an instance of a previously registered TreeNode.
Definition: bt_factory.cpp:292
BT::Tree::tickWhileRunning
NodeStatus tickWhileRunning(std::chrono::milliseconds sleep_time=std::chrono::milliseconds(10))
Definition: bt_factory.cpp:610
BT::Blackboard::Ptr
std::shared_ptr< Blackboard > Ptr
Definition: blackboard.h:35
BT::Tree::getNodesByPath
std::vector< const TreeNode * > getNodesByPath(StringView wildcard_filter) const
Definition: bt_factory.h:166
BT::PortsList
std::unordered_map< std::string, PortInfo > PortsList
Definition: basic_types.h:585
BT::has_static_method_metadata
Definition: basic_types.h:601
BT::BehaviorTreeFactory::registerBuilder
void registerBuilder(const TreeNodeManifest &manifest, const NodeBuilder &builder)
Definition: bt_factory.cpp:140
BT::Tree::sleep
bool sleep(std::chrono::system_clock::duration timeout)
Sleep for a certain amount of time. This sleep could be interrupted by the method TreeNode::emitWakeU...
Definition: bt_factory.cpp:589
json_text
static const char * json_text
Definition: gtest_substitution.cpp:6
BT::Tree::rootNode
TreeNode * rootNode() const
Definition: bt_factory.cpp:579
BT::Tree::tickRoot
NodeStatus tickRoot(TickOption opt, std::chrono::milliseconds sleep_time)
Definition: bt_factory.cpp:640
BT::Tree::~Tree
~Tree()
Definition: bt_factory.cpp:595
BT::BehaviorTreeFactory::registerNodeType
void registerNodeType(const std::string &ID, const PortsList &ports, ExtraArgs... args)
Definition: bt_factory.h:326
BT::BehaviorTreeFactory::createTreeFromText
Tree createTreeFromText(const std::string &text, Blackboard::Ptr blackboard=Blackboard::create())
createTreeFromText will parse the XML directly from string. The XML needs to contain either a single ...
Definition: bt_factory.cpp:395
BT::BehaviorTreeFactory::~BehaviorTreeFactory
~BehaviorTreeFactory()
Definition: bt_factory.cpp:121
BT::Tree::initialize
void initialize()
Definition: bt_factory.cpp:550
BT::Tree::tickExactlyOnce
NodeStatus tickExactlyOnce()
Definition: bt_factory.cpp:600
BT::Tree::Subtree::blackboard
Blackboard::Ptr blackboard
Definition: bt_factory.h:99
BT::TreeNode::Instantiate
static std::unique_ptr< TreeNode > Instantiate(const std::string &name, const NodeConfig &config, ExtraArgs... args)
Definition: tree_node.h:347
BT::CreateManifest
TreeNodeManifest CreateManifest(const std::string &ID, PortsList portlist=getProvidedPorts< T >())
Definition: bt_factory.h:42
BT::BehaviorTreeFactory::PImpl
Definition: bt_factory.cpp:32
BT::Tree::wake_up_
std::shared_ptr< WakeUpSignal > wake_up_
Definition: bt_factory.h:186
magic_enum::detail::entries
constexpr auto entries(std::index_sequence< I... >) noexcept
Definition: magic_enum.hpp:839
BT::TreeNodeManifest
This information is used mostly by the XMLParser.
Definition: tree_node.h:35
BT::Tree::Subtree::instance_name
std::string instance_name
Definition: bt_factory.h:100
BT::ExportTreeToJSON
nlohmann::json ExportTreeToJSON(const BT::Tree &tree)
ExportTreeToJSON it calls ExportBlackboardToJSON for all the blackboards in the tree.
Definition: bt_factory.cpp:701
behavior_tree.h
BT::ImportTreeFromJSON
void ImportTreeFromJSON(const nlohmann::json &json, BT::Tree &tree)
ImportTreeFromJSON it calls ImportBlackboardFromJSON for all the blackboards in the tree.
Definition: bt_factory.cpp:717
BT::BehaviorTreeFactory::registerNodeType
void registerNodeType(const std::string &ID, ExtraArgs... args)
Definition: bt_factory.h:362
BT::Blackboard
The Blackboard is the mechanism used by BehaviorTrees to exchange typed data.
Definition: blackboard.h:32
BT::BehaviorTreeFactory
The BehaviorTreeFactory is used to create instances of a TreeNode at run-time.
Definition: bt_factory.h:209
BT::Tree::WHILE_RUNNING
@ WHILE_RUNNING
Definition: bt_factory.h:192
BT::KeyValueVector
std::vector< std::pair< std::string, std::string > > KeyValueVector
Definition: basic_types.h:66
BT::BehaviorTreeFactory::createTreeFromFile
Tree createTreeFromFile(const std::filesystem::path &file_path, Blackboard::Ptr blackboard=Blackboard::create())
createTreeFromFile will parse the XML from a given file. The XML needs to contain either a single <Be...
Definition: bt_factory.cpp:413
BT::Blackboard::create
static Blackboard::Ptr create(Blackboard::Ptr parent={})
Definition: blackboard.h:63
BT::has_static_method_providedPorts
Definition: basic_types.h:588
BT::BehaviorTreeFactory::builders
const std::unordered_map< std::string, NodeBuilder > & builders() const
All the builders. Made available mostly for debug purposes.
Definition: bt_factory.cpp:379
BT::Tree::subtrees
std::vector< Subtree::Ptr > subtrees
Definition: bt_factory.h:104
BT::Tree::haltTree
void haltTree()
Definition: bt_factory.cpp:562
BT::BehaviorTreeFactory::registerSimpleDecorator
void registerSimpleDecorator(const std::string &ID, const SimpleDecoratorNode::TickFunctor &tick_functor, PortsList ports={})
registerSimpleDecorator help you register nodes of type SimpleDecoratorNode.
Definition: bt_factory.cpp:179
BT::Tree::Subtree::tree_ID
std::string tree_ID
Definition: bt_factory.h:101
BT::BlackboardBackup
std::vector< Blackboard::Ptr > BlackboardBackup(const BT::Tree &tree)
BlackboardBackup uses Blackboard::cloneInto to backup all the blackboards of the tree.
Definition: bt_factory.cpp:689
BT::BehaviorTreeFactory::registerBehaviorTreeFromFile
void registerBehaviorTreeFromFile(const std::filesystem::path &filename)
registerBehaviorTreeFromFile. Load the definition of an entire behavior tree, but don't instantiate i...
Definition: bt_factory.cpp:271
BT::BehaviorTreeFactory::SubstitutionRule
std::variant< std::string, TestNodeConfig > SubstitutionRule
Definition: bt_factory.h:473
json
basic_json<> json
default specialization
Definition: json.hpp:3422
lexy::_detail::is_constructible
constexpr auto is_constructible
Definition: object.hpp:18
BT::BehaviorTreeFactory::registerBehaviorTreeFromText
void registerBehaviorTreeFromText(const std::string &xml_text)
Definition: bt_factory.cpp:277
BT::SimpleConditionNode::TickFunctor
std::function< NodeStatus(TreeNode &)> TickFunctor
Definition: condition_node.h:53
BT::Tree::rootBlackboard
Blackboard::Ptr rootBlackboard()
Definition: bt_factory.cpp:615
BT::BehaviorTreeFactory::addSubstitutionRule
void addSubstitutionRule(StringView filter, SubstitutionRule rule)
addSubstitutionRule replace a node with another one when the tree is created. If the rule ia a string...
Definition: bt_factory.cpp:475
BT::Tree::TickOption
TickOption
Definition: bt_factory.h:188
lexyd::opt
constexpr auto opt(Rule)
Definition: option.hpp:81
BT::NodeBuilder
std::function< std::unique_ptr< TreeNode >(const std::string &, const NodeConfig &)> NodeBuilder
The term "Builder" refers to the Builder Pattern (https://en.wikipedia.org/wiki/Builder_pattern)
Definition: bt_factory.h:31
BT::NodeConfig
Definition: tree_node.h:73
BT::Tree::applyVisitor
void applyVisitor(const std::function< void(const TreeNode *)> &visitor)
Definition: bt_factory.cpp:624
BT::BehaviorTreeFactory::registerSimpleCondition
void registerSimpleCondition(const std::string &ID, const SimpleConditionNode::TickFunctor &tick_functor, PortsList ports={})
registerSimpleCondition help you register nodes of type SimpleConditionNode.
Definition: bt_factory.cpp:153
xml_text
static const char * xml_text
Definition: ex01_wrap_legacy.cpp:52
BT::BehaviorTreeFactory::registerScriptingEnums
void registerScriptingEnums()
registerScriptingEnums is syntactic sugar to automatically register multiple enums....
Definition: bt_factory.h:462
BT::Tree::EXACTLY_ONCE
@ EXACTLY_ONCE
Definition: bt_factory.h:190
BT::SimpleActionNode::TickFunctor
std::function< NodeStatus(TreeNode &)> TickFunctor
Definition: action_node.h:82
BT::BehaviorTreeFactory::registerFromROSPlugins
void registerFromROSPlugins()
registerFromROSPlugins finds all shared libraries that export ROS plugins for behaviortree_cpp,...
Definition: bt_factory.cpp:263
BT::NodeStatus
NodeStatus
Definition: basic_types.h:33
BT::BlackboardClone
void BlackboardClone(const Blackboard &src, Blackboard &dst)
BlackboardClone make a copy of the content of the blackboard.
BT::Parser
The BehaviorTreeParser is a class used to read the model of a BehaviorTree from file or text and inst...
Definition: bt_parser.h:26
BT::BehaviorTreeFactory::registerSimpleAction
void registerSimpleAction(const std::string &ID, const SimpleActionNode::TickFunctor &tick_functor, PortsList ports={})
registerSimpleAction help you register nodes of type SimpleActionNode.
Definition: bt_factory.cpp:166
BT::Tree::uid_counter_
uint16_t uid_counter_
Definition: bt_factory.h:197


behaviortree_cpp_v4
Author(s): Davide Faconti
autogenerated on Fri Dec 13 2024 03:19:16