19 #include <unordered_map> 20 #include <unordered_set> 30 typedef std::function<std::unique_ptr<TreeNode>(
const std::string&,
31 const NodeConfiguration&)>
39 typename std::is_constructible<T, const std::string&, const NodeConfiguration&>;
48 if (config.input_ports.empty() && config.output_ports.empty() &&
51 return std::make_unique<T>(name);
53 return std::make_unique<T>(name, config);
63 return std::unique_ptr<TreeNode>(
new T(name, params));
73 return std::unique_ptr<TreeNode>(
new T(name));
79 PortsList portlist = getProvidedPorts<T>())
81 return {getType<T>(), ID, portlist, {}};
84 #ifdef BT_PLUGIN_EXPORT 87 #define BTCPP_EXPORT extern "C" __declspec(dllexport) 90 #define BTCPP_EXPORT extern "C" __attribute__ ((visibility ("default"))) 94 #define BTCPP_EXPORT static 112 #define BT_REGISTER_NODES(factory) \ 113 BTCPP_EXPORT void BT_RegisterNodesFromPlugin(BT::BehaviorTreeFactory& factory) 130 std::unordered_map<std::string, TreeNodeManifest>
manifests;
141 (*this) = std::move(other);
146 nodes = std::move(other.nodes);
147 blackboard_stack = std::move(other.blackboard_stack);
148 manifests = std::move(other.manifests);
155 wake_up_ = std::make_shared<WakeUpSignal>();
156 for (
auto& node : nodes)
183 return nodes.empty() ? nullptr : nodes.front().get();
200 this->
sleep(sleep_time);
232 void sleep(std::chrono::system_clock::duration timeout);
257 bool unregisterBuilder(
const std::string& ID);
266 template <
typename T>
269 auto manifest = CreateManifest<T>(ID);
270 registerBuilder(manifest, builder);
281 void registerSimpleAction(
const std::string& ID,
292 void registerSimpleCondition(
const std::string& ID,
303 void registerSimpleDecorator(
const std::string& ID,
312 void registerFromPlugin(
const std::string& file_path);
319 void registerFromROSPlugins();
331 void registerBehaviorTreeFromFile(
const std::string& filename);
335 void registerBehaviorTreeFromText(
const std::string&
xml_text);
339 std::vector<std::string> registeredBehaviorTrees()
const;
344 void clearRegisteredBehaviorTrees();
354 std::unique_ptr<TreeNode> instantiateTreeNode(
const std::string& name,
355 const std::string& ID,
363 template <
typename T>
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 " 372 "DecoratorNode, ControlNode or ConditionNode");
374 static_assert(!std::is_abstract<T>::value,
"[registerNode]: Some methods are pure " 376 "Did you override the methods tick() and " 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;
385 static_assert(default_constructable || param_constructable,
"[registerNode]: the " 386 "registered class must " 388 "least one of these two " 390 " (const std::string&, " 392 "NodeConfiguration&) or " 399 static_assert(!(param_constructable && !has_static_ports_list),
"[registerNode]: you " 405 "providedPorts();\n");
407 static_assert(!(has_static_ports_list && !param_constructable),
"[registerNode]: " 415 "std::string&, const " 416 "NodeParameters&)\n");
418 registerBuilder(CreateManifest<T>(ID), CreateBuilder<T>());
421 template <
typename T>
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 " 430 "DecoratorNode, ControlNode or ConditionNode");
432 static_assert(!std::is_abstract<T>::value,
"[registerNode]: Some methods are pure " 434 "Did you override the methods tick() and " 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;
443 static_assert(default_constructable || param_constructable,
"[registerNode]: the " 444 "registered class must " 446 "least one of these two " 447 "constructors: (const " 448 "std::string&, const " 449 "NodeConfiguration&) or " 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 " 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");
463 registerBuilder(CreateManifest<T>(ID, ports), CreateBuilder<T>());
467 const std::unordered_map<std::string, NodeBuilder>& builders()
const;
470 const std::unordered_map<std::string, TreeNodeManifest>&
manifests()
const;
473 const std::set<std::string>& builtinNodes()
const;
475 Tree createTreeFromText(
const std::string& text,
478 Tree createTreeFromFile(
const std::string& file_path,
481 Tree createTree(
const std::string& tree_name,
486 void addDescriptionToManifest(
const std::string& node_id,
487 const std::string& description);
491 std::unordered_map<std::string, TreeNodeManifest>
manifests_;
501 #endif // BT_FACTORY_H constexpr const char * PLUGIN_SYMBOL
typename std::enable_if< Predicate::value >::type * enable_if
void sleep(std::chrono::system_clock::duration timeout)
std::shared_ptr< WakeUpSignal > wake_up_
static Blackboard::Ptr create(Blackboard::Ptr parent={})
void registerNodeType(const std::string &ID)
The BehaviorTreeParser is a class used to read the model of a BehaviorTree from file or text and inst...
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) ...
NodeBuilder CreateBuilder(typename std::enable_if< has_default_constructor< T >::value &&has_params_constructor< T >::value >::type *=nullptr)
std::unordered_map< std::string, NodeBuilder > builders_
std::set< std::string > builtin_IDs_
std::vector< Blackboard::Ptr > blackboard_stack
std::shared_ptr< Blackboard > Ptr
TreeNode * rootNode() const
This information is used mostly by the XMLParser.
std::unordered_map< std::string, TreeNodeManifest > manifests_
Blackboard::Ptr rootBlackboard()
Tree & operator=(Tree &&other)
static const char * xml_text
void registerBuilder(const std::string &ID, const NodeBuilder &builder)
typename std::is_constructible< T, const std::string &, const NodeConfiguration & > has_params_constructor
The BehaviorTreeFactory is used to create instances of a TreeNode at run-time.
TreeNodeManifest CreateManifest(const std::string &ID, PortsList portlist=getProvidedPorts< T >())
NodeStatus tickRoot()
tickRoot send the tick signal to the root node. It will propagate through the entire tree...
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.
Tree & operator=(const Tree &)=delete
typename std::is_constructible< T, const std::string & > has_default_constructor
Struct used to store a tree. If this object goes out of scope, the tree is destroyed.
Abstract base class for Behavior Tree Nodes.
std::function< NodeStatus(TreeNode &)> TickFunctor
std::unordered_map< std::string, PortInfo > PortsList
std::vector< TreeNode::Ptr > nodes
std::unordered_map< std::string, TreeNodeManifest > manifests
std::unordered_map< std::string, Any > behavior_tree_definitions_
virtual BT::NodeStatus executeTick()
The method that should be used to invoke tick() and setStatus();.
void setStatus(NodeStatus new_status)
void registerNodeType(const std::string &ID, PortsList ports)
std::shared_ptr< BT::Parser > parser_
std::function< NodeStatus(TreeNode &)> TickFunctor
void applyRecursiveVisitor(const TreeNode *root_node, const std::function< void(const TreeNode *)> &visitor)