bt_factory.h
Go to the documentation of this file.
1 /* Copyright (C) 2018 Michele Colledanchise - All Rights Reserved
2  * Copyright (C) 2018-2020 Davide Faconti, Eurecat - 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 <functional>
18 #include <memory>
19 #include <unordered_map>
20 #include <unordered_set>
21 #include <cstring>
22 #include <algorithm>
23 #include <set>
24 
26 
27 namespace BT
28 {
30 typedef std::function<std::unique_ptr<TreeNode>(const std::string&,
31  const NodeConfiguration&)>
33 
34 template <typename T>
35 using has_default_constructor = typename std::is_constructible<T, const std::string&>;
36 
37 template <typename T>
39  typename std::is_constructible<T, const std::string&, const NodeConfiguration&>;
40 
41 template <typename T>
42 inline NodeBuilder
44  has_params_constructor<T>::value>::type* = nullptr)
45 {
46  return [](const std::string& name, const NodeConfiguration& config) {
47  // Special case. Use default constructor if parameters are empty
48  if (config.input_ports.empty() && config.output_ports.empty() &&
50  {
51  return std::make_unique<T>(name);
52  }
53  return std::make_unique<T>(name, config);
54  };
55 }
56 
57 template <typename T>
58 inline NodeBuilder
60  has_params_constructor<T>::value>::type* = nullptr)
61 {
62  return [](const std::string& name, const NodeConfiguration& params) {
63  return std::unique_ptr<TreeNode>(new T(name, params));
64  };
65 }
66 
67 template <typename T>
68 inline NodeBuilder
70  !has_params_constructor<T>::value>::type* = nullptr)
71 {
72  return [](const std::string& name, const NodeConfiguration&) {
73  return std::unique_ptr<TreeNode>(new T(name));
74  };
75 }
76 
77 template <typename T>
78 inline TreeNodeManifest CreateManifest(const std::string& ID,
79  PortsList portlist = getProvidedPorts<T>())
80 {
81  return {getType<T>(), ID, portlist, {}};
82 }
83 
84 #ifdef BT_PLUGIN_EXPORT
85 
86 #if defined(_WIN32)
87  #define BTCPP_EXPORT extern "C" __declspec(dllexport)
88 #else
89  // Unix-like OSes
90  #define BTCPP_EXPORT extern "C" __attribute__ ((visibility ("default")))
91 #endif
92 
93 #else
94  #define BTCPP_EXPORT static
95 #endif
96 /* Use this macro to automatically register one or more custom Nodes
97 * into a factory. For instance:
98 *
99 * BT_REGISTER_NODES(factory)
100 * {
101 * factory.registerNodeType<MoveBaseAction>("MoveBase");
102 * }
103 *
104 * IMPORTANT: this function MUST be declared in a cpp file, NOT a header file.
105 * In your cake, you must add the definition [BT_PLUGIN_EXPORT] with:
106 *
107 * target_compile_definitions(my_plugin_target PRIVATE BT_PLUGIN_EXPORT )
108 
109 * See examples in sample_nodes directory.
110 */
111 
112 #define BT_REGISTER_NODES(factory) \
113  BTCPP_EXPORT void BT_RegisterNodesFromPlugin(BT::BehaviorTreeFactory& factory)
114 
115 constexpr const char* PLUGIN_SYMBOL = "BT_RegisterNodesFromPlugin";
116 
125 class Tree
126 {
127 public:
128  std::vector<TreeNode::Ptr> nodes;
129  std::vector<Blackboard::Ptr> blackboard_stack;
130  std::unordered_map<std::string, TreeNodeManifest> manifests;
131 
133  {}
134 
135  // non-copyable. Only movable
136  Tree(const Tree&) = delete;
137  Tree& operator=(const Tree&) = delete;
138 
139  Tree(Tree&& other)
140  {
141  (*this) = std::move(other);
142  }
143 
144  Tree& operator=(Tree&& other)
145  {
146  nodes = std::move(other.nodes);
147  blackboard_stack = std::move(other.blackboard_stack);
148  manifests = std::move(other.manifests);
149  wake_up_ = other.wake_up_;
150  return *this;
151  }
152 
153  void initialize()
154  {
155  wake_up_ = std::make_shared<WakeUpSignal>();
156  for (auto& node : nodes)
157  {
158  node->setWakeUpInstance(wake_up_);
159  }
160  }
161 
162  void haltTree()
163  {
164  if (!rootNode())
165  {
166  return;
167  }
168  // the halt should propagate to all the node if the nodes
169  // have been implemented correctly
170  rootNode()->halt();
172 
173  //but, just in case.... this should be no-op
174  auto visitor = [](BT::TreeNode* node) {
175  node->halt();
176  node->setStatus(BT::NodeStatus::IDLE);
177  };
179  }
180 
182  {
183  return nodes.empty() ? nullptr : nodes.front().get();
184  }
185 
194  NodeStatus tickRootWhileRunning(std::chrono::milliseconds sleep_time = std::chrono::milliseconds(10))
195  {
196  NodeStatus status = tickRoot();
197 
198  while (status == NodeStatus::RUNNING)
199  {
200  this->sleep(sleep_time);
201  status = tickRoot();
202  }
203  return status;
204  }
205 
211  {
212  if (!wake_up_)
213  {
214  initialize();
215  }
216 
217  if (!rootNode())
218  {
219  throw RuntimeError("Empty Tree");
220  }
221  NodeStatus ret = rootNode()->executeTick();
222  if (ret == NodeStatus::SUCCESS || ret == NodeStatus::FAILURE)
223  {
225  }
226  return ret;
227  }
228 
232  void sleep(std::chrono::system_clock::duration timeout);
233 
234  ~Tree();
235 
237 
238 private:
239  std::shared_ptr<WakeUpSignal> wake_up_;
240 };
241 
242 class Parser;
243 
252 {
253 public:
255 
257  bool unregisterBuilder(const std::string& ID);
258 
264  void registerBuilder(const TreeNodeManifest& manifest, const NodeBuilder& builder);
265 
266  template <typename T>
267  void registerBuilder(const std::string& ID, const NodeBuilder& builder)
268  {
269  auto manifest = CreateManifest<T>(ID);
270  registerBuilder(manifest, builder);
271  }
272 
281  void registerSimpleAction(const std::string& ID,
282  const SimpleActionNode::TickFunctor& tick_functor,
283  PortsList ports = {});
292  void registerSimpleCondition(const std::string& ID,
293  const SimpleConditionNode::TickFunctor& tick_functor,
294  PortsList ports = {});
303  void registerSimpleDecorator(const std::string& ID,
304  const SimpleDecoratorNode::TickFunctor& tick_functor,
305  PortsList ports = {});
306 
312  void registerFromPlugin(const std::string& file_path);
313 
319  void registerFromROSPlugins();
320 
331  void registerBehaviorTreeFromFile(const std::string& filename);
332 
335  void registerBehaviorTreeFromText(const std::string& xml_text);
336 
339  std::vector<std::string> registeredBehaviorTrees() const;
340 
344  void clearRegisteredBehaviorTrees();
345 
354  std::unique_ptr<TreeNode> instantiateTreeNode(const std::string& name,
355  const std::string& ID,
356  const NodeConfiguration& config) const;
357 
363  template <typename T>
364  void registerNodeType(const std::string& ID)
365  {
366  static_assert(std::is_base_of<ActionNodeBase, T>::value ||
367  std::is_base_of<ControlNode, T>::value ||
368  std::is_base_of<DecoratorNode, T>::value ||
369  std::is_base_of<ConditionNode, T>::value,
370  "[registerNode]: accepts only classed derived from either "
371  "ActionNodeBase, "
372  "DecoratorNode, ControlNode or ConditionNode");
373 
374  static_assert(!std::is_abstract<T>::value, "[registerNode]: Some methods are pure "
375  "virtual. "
376  "Did you override the methods tick() and "
377  "halt()?");
378 
379  constexpr bool default_constructable =
380  std::is_constructible<T, const std::string&>::value;
381  constexpr bool param_constructable =
382  std::is_constructible<T, const std::string&, const NodeConfiguration&>::value;
383  constexpr bool has_static_ports_list = has_static_method_providedPorts<T>::value;
384 
385  static_assert(default_constructable || param_constructable, "[registerNode]: the "
386  "registered class must "
387  "have at "
388  "least one of these two "
389  "constructors: "
390  " (const std::string&, "
391  "const "
392  "NodeConfiguration&) or "
393  "(const "
394  "std::string&).\n"
395  "Check also if the "
396  "constructor "
397  "is public!");
398 
399  static_assert(!(param_constructable && !has_static_ports_list), "[registerNode]: you "
400  "MUST "
401  "implement the "
402  "static "
403  "method: "
404  " PortsList "
405  "providedPorts();\n");
406 
407  static_assert(!(has_static_ports_list && !param_constructable), "[registerNode]: "
408  "since you "
409  "have a static "
410  "method "
411  "providedPorts(), "
412  "you MUST add a "
413  "constructor sign "
414  "signature (const "
415  "std::string&, const "
416  "NodeParameters&)\n");
417 
418  registerBuilder(CreateManifest<T>(ID), CreateBuilder<T>());
419  }
420 
421  template <typename T>
422  void registerNodeType(const std::string& ID, PortsList ports)
423  {
424  static_assert(std::is_base_of<ActionNodeBase, T>::value ||
425  std::is_base_of<ControlNode, T>::value ||
426  std::is_base_of<DecoratorNode, T>::value ||
427  std::is_base_of<ConditionNode, T>::value,
428  "[registerNode]: accepts only classed derived from either "
429  "ActionNodeBase, "
430  "DecoratorNode, ControlNode or ConditionNode");
431 
432  static_assert(!std::is_abstract<T>::value, "[registerNode]: Some methods are pure "
433  "virtual. "
434  "Did you override the methods tick() and "
435  "halt()?");
436 
437  constexpr bool default_constructable =
438  std::is_constructible<T, const std::string&>::value;
439  constexpr bool param_constructable =
440  std::is_constructible<T, const std::string&, const NodeConfiguration&>::value;
441  constexpr bool has_static_ports_list = has_static_method_providedPorts<T>::value;
442 
443  static_assert(default_constructable || param_constructable, "[registerNode]: the "
444  "registered class must "
445  "have at "
446  "least one of these two "
447  "constructors: (const "
448  "std::string&, const "
449  "NodeConfiguration&) or "
450  "(const "
451  "std::string&).");
452 
453  static_assert(!has_static_ports_list, "[registerNode]: ports are passed to this node "
454  "explicitly. The static method"
455  "providedPorts() should be removed to avoid "
456  "ambiguities\n");
457 
458  static_assert(param_constructable, "[registerNode]: since this node has ports, "
459  "you MUST add a constructor sign signature (const "
460  "std::string&, const "
461  "NodeParameters&)\n");
462 
463  registerBuilder(CreateManifest<T>(ID, ports), CreateBuilder<T>());
464  }
465 
467  const std::unordered_map<std::string, NodeBuilder>& builders() const;
468 
470  const std::unordered_map<std::string, TreeNodeManifest>& manifests() const;
471 
473  const std::set<std::string>& builtinNodes() const;
474 
475  Tree createTreeFromText(const std::string& text,
476  Blackboard::Ptr blackboard = Blackboard::create());
477 
478  Tree createTreeFromFile(const std::string& file_path,
479  Blackboard::Ptr blackboard = Blackboard::create());
480 
481  Tree createTree(const std::string& tree_name,
482  Blackboard::Ptr blackboard = Blackboard::create());
483 
486  void addDescriptionToManifest(const std::string& node_id,
487  const std::string& description);
488 
489 private:
490  std::unordered_map<std::string, NodeBuilder> builders_;
491  std::unordered_map<std::string, TreeNodeManifest> manifests_;
492  std::set<std::string> builtin_IDs_;
493  std::unordered_map<std::string, Any> behavior_tree_definitions_;
494 
495  std::shared_ptr<BT::Parser> parser_;
496  // clang-format on
497 };
498 
499 } // namespace BT
500 
501 #endif // BT_FACTORY_H
constexpr const char * PLUGIN_SYMBOL
Definition: bt_factory.h:115
typename std::enable_if< Predicate::value >::type * enable_if
Definition: basic_types.h:175
void sleep(std::chrono::system_clock::duration timeout)
Definition: bt_factory.cpp:332
std::shared_ptr< WakeUpSignal > wake_up_
Definition: bt_factory.h:239
static Blackboard::Ptr create(Blackboard::Ptr parent={})
Definition: blackboard.h:36
virtual void halt()=0
void registerNodeType(const std::string &ID)
Definition: bt_factory.h:364
The BehaviorTreeParser is a class used to read the model of a BehaviorTree from file or text and inst...
Definition: bt_parser.h:25
std::function< NodeStatus(NodeStatus, TreeNode &)> TickFunctor
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) ...
Definition: bt_factory.h:32
NodeBuilder CreateBuilder(typename std::enable_if< has_default_constructor< T >::value &&has_params_constructor< T >::value >::type *=nullptr)
Definition: bt_factory.h:43
std::unordered_map< std::string, NodeBuilder > builders_
Definition: bt_factory.h:490
Tree(Tree &&other)
Definition: bt_factory.h:139
std::set< std::string > builtin_IDs_
Definition: bt_factory.h:492
void haltTree()
Definition: bt_factory.h:162
std::vector< Blackboard::Ptr > blackboard_stack
Definition: bt_factory.h:129
std::shared_ptr< Blackboard > Ptr
Definition: blackboard.h:25
TreeNode * rootNode() const
Definition: bt_factory.h:181
This information is used mostly by the XMLParser.
Definition: tree_node.h:34
std::unordered_map< std::string, TreeNodeManifest > manifests_
Definition: bt_factory.h:491
Blackboard::Ptr rootBlackboard()
Definition: bt_factory.cpp:342
Tree & operator=(Tree &&other)
Definition: bt_factory.h:144
static const char * xml_text
void registerBuilder(const std::string &ID, const NodeBuilder &builder)
Definition: bt_factory.h:267
typename std::is_constructible< T, const std::string &, const NodeConfiguration & > has_params_constructor
Definition: bt_factory.h:39
string manifest
The BehaviorTreeFactory is used to create instances of a TreeNode at run-time.
Definition: bt_factory.h:251
TreeNodeManifest CreateManifest(const std::string &ID, PortsList portlist=getProvidedPorts< T >())
Definition: bt_factory.h:78
NodeStatus tickRoot()
tickRoot send the tick signal to the root node. It will propagate through the entire tree...
Definition: bt_factory.h:210
NodeStatus tickRootWhileRunning(std::chrono::milliseconds sleep_time=std::chrono::milliseconds(10))
tickRootWhileRunning imply execute tickRoot in a loop as long as the status is RUNNING.
Definition: bt_factory.h:194
Tree & operator=(const Tree &)=delete
typename std::is_constructible< T, const std::string & > has_default_constructor
Definition: bt_factory.h:35
Struct used to store a tree. If this object goes out of scope, the tree is destroyed.
Definition: bt_factory.h:125
Abstract base class for Behavior Tree Nodes.
Definition: tree_node.h:55
std::function< NodeStatus(TreeNode &)> TickFunctor
Definition: action_node.h:81
std::unordered_map< std::string, PortInfo > PortsList
Definition: basic_types.h:333
std::vector< TreeNode::Ptr > nodes
Definition: bt_factory.h:128
std::unordered_map< std::string, TreeNodeManifest > manifests
Definition: bt_factory.h:130
NodeStatus
Definition: basic_types.h:35
std::unordered_map< std::string, Any > behavior_tree_definitions_
Definition: bt_factory.h:493
virtual BT::NodeStatus executeTick()
The method that should be used to invoke tick() and setStatus();.
Definition: tree_node.cpp:32
void initialize()
Definition: bt_factory.h:153
void setStatus(NodeStatus new_status)
Definition: tree_node.cpp:63
void registerNodeType(const std::string &ID, PortsList ports)
Definition: bt_factory.h:422
std::shared_ptr< BT::Parser > parser_
Definition: bt_factory.h:495
std::function< NodeStatus(TreeNode &)> TickFunctor
void applyRecursiveVisitor(const TreeNode *root_node, const std::function< void(const TreeNode *)> &visitor)


behaviortree_cpp_v3
Author(s): Michele Colledanchise, Davide Faconti
autogenerated on Mon Jul 3 2023 02:50:14