Go to the documentation of this file.
20 #include <unordered_map>
31 std::function<std::unique_ptr<TreeNode>(
const std::string&,
const NodeConfig&)>;
33 template <
typename T,
typename... Args>
36 return [=](
const std::string& name,
const NodeConfig& config) {
43 PortsList portlist = getProvidedPorts<T>())
47 return { getType<T>(), ID, portlist, T::metadata() };
49 return { getType<T>(), ID, portlist, {} };
52 #ifdef BT_PLUGIN_EXPORT
55 #define BTCPP_EXPORT extern "C" __declspec(dllexport)
58 #define BTCPP_EXPORT extern "C" __attribute__((visibility("default")))
62 #define BTCPP_EXPORT static
80 #define BT_REGISTER_NODES(factory) \
81 BTCPP_EXPORT void BT_RegisterNodesFromPlugin(BT::BehaviorTreeFactory& factory)
97 using Ptr = std::shared_ptr<Subtree>;
98 std::vector<TreeNode::Ptr>
nodes;
105 std::unordered_map<std::string, TreeNodeManifest>
manifests;
128 bool sleep(std::chrono::system_clock::duration timeout);
147 tickWhileRunning(std::chrono::milliseconds sleep_time = std::chrono::milliseconds(10));
157 [[nodiscard]] uint16_t
getUID();
164 template <
typename NodeType = BT::TreeNode>
165 [[nodiscard]] std::vector<const TreeNode*>
168 std::vector<const TreeNode*> nodes;
171 for(
auto const& node : subtree->nodes)
173 if(
auto node_recast =
dynamic_cast<const NodeType*
>(node.get()))
177 nodes.push_back(node.get());
231 template <
typename T>
234 auto manifest = CreateManifest<T>(ID);
320 const std::string& name,
const std::string& ID,
const NodeConfig& config)
const;
325 template <
typename T,
typename... ExtraArgs>
332 "[registerNode]: accepts only classed derived from either "
334 "DecoratorNode, ControlNode or ConditionNode");
336 constexpr
bool default_constructable =
338 constexpr
bool param_constructable =
340 ExtraArgs...>::value;
344 "[registerNode]: Some methods are pure virtual. "
345 "Did you override the methods tick() and halt()?");
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!)");
353 registerBuilder(CreateManifest<T>(ID, ports), CreateBuilder<T>(args...));
361 template <
typename T,
typename... ExtraArgs>
364 if constexpr(std::is_abstract_v<T>)
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?");
373 constexpr
bool param_constructable =
375 ExtraArgs...>::value;
379 static_assert(!(param_constructable && !has_static_ports_list),
380 "[registerNode]: you MUST implement the static method:\n"
381 " PortsList providedPorts();\n");
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");
389 registerNodeType<T>(ID, getProvidedPorts<T>(), args...);
393 [[nodiscard]]
const std::unordered_map<std::string, NodeBuilder>&
builders()
const;
396 [[nodiscard]]
const std::unordered_map<std::string, TreeNodeManifest>&
400 [[nodiscard]]
const std::set<std::string>&
builtinNodes()
const;
461 template <
typename EnumType>
464 constexpr
auto entries = magic_enum::enum_entries<EnumType>();
500 [[nodiscard]]
const std::unordered_map<std::string, SubstitutionRule>&
505 std::unique_ptr<PImpl>
_p;
548 #endif // BT_FACTORY_H
const std::set< std::string > & builtinNodes() const
List of builtin IDs.
void BlackboardRestore(const std::vector< Blackboard::Ptr > &backup, BT::Tree &tree)
BlackboardRestore uses Blackboard::cloneInto to restore all the blackboards of the tree.
NodeType
Enumerates the possible types of nodes.
std::vector< std::string > registeredBehaviorTrees() const
Tree createTree(const std::string &tree_name, Blackboard::Ptr blackboard=Blackboard::create())
NodeBuilder CreateBuilder(Args... args)
bool unregisterBuilder(const std::string &ID)
Remove a registered ID.
void registerBuilder(const std::string &ID, const NodeBuilder &builder)
std::function< NodeStatus(NodeStatus, TreeNode &)> TickFunctor
Tree & operator=(const Tree &)=delete
BehaviorTreeFactory & operator=(const BehaviorTreeFactory &other)=delete
std::vector< TreeNode::Ptr > nodes
const std::unordered_map< std::string, SubstitutionRule > & substitutionRules() const
substitutionRules return the current substitution rules.
std::unique_ptr< PImpl > _p
std::string_view StringView
void loadSubstitutionRuleFromJSON(const std::string &json_text)
loadSubstitutionRuleFromJSON will parse a JSON file to create a set of substitution rules....
void registerFromPlugin(const std::string &file_path)
registerFromPlugin load a shared library and execute the function BT_REGISTER_NODES (see macro).
Abstract base class for Behavior Tree Nodes.
Struct used to store a tree. If this object goes out of scope, the tree is destroyed.
std::unordered_map< std::string, TreeNodeManifest > manifests
void addMetadataToManifest(const std::string &node_id, const KeyValueVector &metadata)
NodeStatus tickOnce()
by default, tickOnce() sends a single tick, BUT as long as there is at least one node of the tree inv...
namespace for Niels Lohmann
constexpr const char * PLUGIN_SYMBOL
void clearRegisteredBehaviorTrees()
Clear previously-registered behavior trees.
constexpr E value(std::size_t i) noexcept
void clearSubstitutionRules()
void registerScriptingEnum(StringView name, int value)
Add an Enum to the scripting language. For instance if you do:
const std::unordered_map< std::string, TreeNodeManifest > & manifests() const
Manifests of all the registered TreeNodes.
bool WildcardMatch(const std::string &str, StringView filter)
std::shared_ptr< Subtree > Ptr
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.
NodeStatus tickWhileRunning(std::chrono::milliseconds sleep_time=std::chrono::milliseconds(10))
std::shared_ptr< Blackboard > Ptr
std::vector< const TreeNode * > getNodesByPath(StringView wildcard_filter) const
std::unordered_map< std::string, PortInfo > PortsList
void registerBuilder(const TreeNodeManifest &manifest, const NodeBuilder &builder)
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...
static const char * json_text
TreeNode * rootNode() const
NodeStatus tickRoot(TickOption opt, std::chrono::milliseconds sleep_time)
void registerNodeType(const std::string &ID, const PortsList &ports, ExtraArgs... args)
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 ...
NodeStatus tickExactlyOnce()
Blackboard::Ptr blackboard
static std::unique_ptr< TreeNode > Instantiate(const std::string &name, const NodeConfig &config, ExtraArgs... args)
TreeNodeManifest CreateManifest(const std::string &ID, PortsList portlist=getProvidedPorts< T >())
std::shared_ptr< WakeUpSignal > wake_up_
constexpr auto entries(std::index_sequence< I... >) noexcept
This information is used mostly by the XMLParser.
std::string instance_name
nlohmann::json ExportTreeToJSON(const BT::Tree &tree)
ExportTreeToJSON it calls ExportBlackboardToJSON for all the blackboards in the tree.
void ImportTreeFromJSON(const nlohmann::json &json, BT::Tree &tree)
ImportTreeFromJSON it calls ImportBlackboardFromJSON for all the blackboards in the tree.
void registerNodeType(const std::string &ID, ExtraArgs... args)
The Blackboard is the mechanism used by BehaviorTrees to exchange typed data.
The BehaviorTreeFactory is used to create instances of a TreeNode at run-time.
std::vector< std::pair< std::string, std::string > > KeyValueVector
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...
static Blackboard::Ptr create(Blackboard::Ptr parent={})
const std::unordered_map< std::string, NodeBuilder > & builders() const
All the builders. Made available mostly for debug purposes.
std::vector< Subtree::Ptr > subtrees
void registerSimpleDecorator(const std::string &ID, const SimpleDecoratorNode::TickFunctor &tick_functor, PortsList ports={})
registerSimpleDecorator help you register nodes of type SimpleDecoratorNode.
std::vector< Blackboard::Ptr > BlackboardBackup(const BT::Tree &tree)
BlackboardBackup uses Blackboard::cloneInto to backup all the blackboards of the tree.
void registerBehaviorTreeFromFile(const std::filesystem::path &filename)
registerBehaviorTreeFromFile. Load the definition of an entire behavior tree, but don't instantiate i...
std::variant< std::string, TestNodeConfig > SubstitutionRule
basic_json<> json
default specialization
constexpr auto is_constructible
void registerBehaviorTreeFromText(const std::string &xml_text)
std::function< NodeStatus(TreeNode &)> TickFunctor
Blackboard::Ptr rootBlackboard()
void addSubstitutionRule(StringView filter, SubstitutionRule rule)
addSubstitutionRule replace a node with another one when the tree is created. If the rule ia a string...
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)
void applyVisitor(const std::function< void(const TreeNode *)> &visitor)
void registerSimpleCondition(const std::string &ID, const SimpleConditionNode::TickFunctor &tick_functor, PortsList ports={})
registerSimpleCondition help you register nodes of type SimpleConditionNode.
static const char * xml_text
void registerScriptingEnums()
registerScriptingEnums is syntactic sugar to automatically register multiple enums....
std::function< NodeStatus(TreeNode &)> TickFunctor
void registerFromROSPlugins()
registerFromROSPlugins finds all shared libraries that export ROS plugins for behaviortree_cpp,...
void BlackboardClone(const Blackboard &src, Blackboard &dst)
BlackboardClone make a copy of the content of the blackboard.
The BehaviorTreeParser is a class used to read the model of a BehaviorTree from file or text and inst...
void registerSimpleAction(const std::string &ID, const SimpleActionNode::TickFunctor &tick_functor, PortsList ports={})
registerSimpleAction help you register nodes of type SimpleActionNode.