26 registerNodeType<FallbackNode>(
"Fallback");
27 registerNodeType<SequenceNode>(
"Sequence");
28 registerNodeType<SequenceStarNode>(
"SequenceStar");
29 registerNodeType<ParallelNode>(
"Parallel");
30 registerNodeType<ReactiveSequence>(
"ReactiveSequence");
31 registerNodeType<ReactiveFallback>(
"ReactiveFallback");
32 registerNodeType<IfThenElseNode>(
"IfThenElse");
33 registerNodeType<WhileDoElseNode>(
"WhileDoElse");
35 registerNodeType<InverterNode>(
"Inverter");
36 registerNodeType<RetryNode>(
"RetryUntilSuccesful");
37 registerNodeType<KeepRunningUntilFailureNode>(
"KeepRunningUntilFailure");
38 registerNodeType<RepeatNode>(
"Repeat");
39 registerNodeType<TimeoutNode<>>(
"Timeout");
40 registerNodeType<DelayNode>(
"Delay");
42 registerNodeType<ForceSuccessNode>(
"ForceSuccess");
43 registerNodeType<ForceFailureNode>(
"ForceFailure");
45 registerNodeType<AlwaysSuccessNode>(
"AlwaysSuccess");
46 registerNodeType<AlwaysFailureNode>(
"AlwaysFailure");
47 registerNodeType<SetBlackboard>(
"SetBlackboard");
49 registerNodeType<SubtreeNode>(
"SubTree");
50 registerNodeType<SubtreePlusNode>(
"SubTreePlus");
52 registerNodeType<BlackboardPreconditionNode<int>>(
"BlackboardCheckInt");
53 registerNodeType<BlackboardPreconditionNode<double>>(
"BlackboardCheckDouble");
54 registerNodeType<BlackboardPreconditionNode<std::string>>(
"BlackboardCheckString");
56 registerNodeType<SwitchNode<2>>(
"Switch2");
57 registerNodeType<SwitchNode<3>>(
"Switch3");
58 registerNodeType<SwitchNode<4>>(
"Switch4");
59 registerNodeType<SwitchNode<5>>(
"Switch5");
60 registerNodeType<SwitchNode<6>>(
"Switch6");
63 registerNodeType<ManualSelectorNode>(
"ManualSelector");
75 throw LogicError(
"You can not remove the builtin registration ID [", ID,
"]");
104 return std::make_unique<SimpleConditionNode>(name, tick_functor, config);
116 return std::make_unique<SimpleActionNode>(name, tick_functor, config);
128 return std::make_unique<SimpleDecoratorNode>(name, tick_functor, config);
138 loader.
load(file_path);
148 std::cout <<
"ERROR loading library [" << file_path <<
"]: can't find symbol [" 156 const char os_pathsep(
';');
158 const char os_pathsep(
':');
164 std::vector<std::string> getCatkinLibraryPaths()
166 std::vector<std::string> lib_paths;
167 const char* env = std::getenv(
"CMAKE_PREFIX_PATH");
170 const std::string env_catkin_prefix_paths(env);
171 std::vector<BT::StringView> catkin_prefix_paths =
175 filesystem::path
path(static_cast<std::string>(catkin_prefix_path));
176 filesystem::path lib(
"lib");
177 lib_paths.push_back((path / lib).str());
185 std::vector<std::string> plugins;
187 std::vector<std::string> catkin_lib_paths = getCatkinLibraryPaths();
189 for (
const auto& plugin : plugins)
192 for (
const auto& lib_path : catkin_lib_paths)
194 const auto full_path = filesystem::path(lib_path) / filename;
195 if (full_path.exists())
197 std::cout <<
"Registering ROS plugins from " << full_path.str() << std::endl;
208 throw RuntimeError(
"Using attribute [ros_pkg] in <include>, but this library was compiled " 209 "without ROS support. Recompile the BehaviorTree.CPP using catkin");
214 const std::string& name,
215 const std::string& ID,
221 std::cerr << ID <<
" not included in this list:" << std::endl;
224 std::cerr << builder_it.first << std::endl;
226 throw RuntimeError(
"BehaviorTreeFactory: ID [", ID,
"] not registered");
229 std::unique_ptr<TreeNode> node = it->second(name, config);
230 node->setRegistrationID( ID );
276 if( blackboard_stack.size() > 0)
278 return blackboard_stack.front();
constexpr const char * PLUGIN_SYMBOL
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) ...
std::unordered_map< std::string, NodeBuilder > builders_
std::set< std::string > builtin_IDs_
std::shared_ptr< Blackboard > Ptr
const std::set< std::string > & builtinNodes() const
List of builtin IDs.
This information is used mostly by the XMLParser.
const std::unordered_map< std::string, NodeBuilder > & builders() const
All the builders. Made available mostly for debug purposes.
std::unordered_map< std::string, TreeNodeManifest > manifests_
Blackboard::Ptr rootBlackboard()
bool hasSymbol(const std::string &name)
Returns true iff a library has been loaded.
std::vector< StringView > splitString(const StringView &strToSplit, char delimeter)
std::unique_ptr< TreeNode > instantiateTreeNode(const std::string &name, const std::string &ID, const NodeConfiguration &config) const
instantiateTreeNode creates an instance of a previously registered TreeNode.
static std::string suffix()
The BehaviorTreeFactory is used to create instances of a TreeNode at run-time.
void * getSymbol(const std::string &name)
nonstd::string_view StringView
std::string registration_ID
Tree createTreeFromText(const std::string &text, Blackboard::Ptr blackboard=Blackboard::create())
void registerFromPlugin(const std::string &file_path)
registerFromPlugin load a shared library and execute the function BT_REGISTER_NODES (see macro)...
Struct used to store a tree. If this object goes out of scope, the tree is destroyed.
Tree instantiateTree(const Blackboard::Ptr &root_blackboard) override
Simple class for manipulating paths on Linux/Windows/Mac OS.
void registerSimpleAction(const std::string &ID, const SimpleActionNode::TickFunctor &tick_functor, PortsList ports={})
registerSimpleAction help you register nodes of type SimpleActionNode.
ROSLIB_DECL void getPlugins(const std::string &package, const std::string &attribute, V_string &plugins, bool force_recrawl=false)
std::function< NodeStatus(TreeNode &)> TickFunctor
void load(const std::string &path, int flags=0)
std::unordered_map< std::string, PortInfo > PortsList
static volatile int count
const std::unordered_map< std::string, TreeNodeManifest > & manifests() const
Manifests of all the registered TreeNodes.
The XMLParser is a class used to read the model of a BehaviorTree from file or text and instantiate t...
std::unordered_map< std::string, TreeNodeManifest > manifests
void loadFromText(const std::string &xml_text) override
void registerBuilder(const TreeNodeManifest &manifest, const NodeBuilder &builder)
The most generic way to register your own builder.
void registerFromROSPlugins()
registerFromROSPlugins finds all shared libraries that export ROS plugins for behaviortree_cpp, and calls registerFromPlugin for each library.
bool unregisterBuilder(const std::string &ID)
Remove a registered ID.
void loadFromFile(const std::string &filename) override
Tree createTreeFromFile(const std::string &file_path, Blackboard::Ptr blackboard=Blackboard::create())
void registerSimpleDecorator(const std::string &ID, const SimpleDecoratorNode::TickFunctor &tick_functor, PortsList ports={})
registerSimpleDecorator help you register nodes of type SimpleDecoratorNode.
void registerSimpleCondition(const std::string &ID, const SimpleConditionNode::TickFunctor &tick_functor, PortsList ports={})
registerSimpleCondition help you register nodes of type SimpleConditionNode.
std::function< NodeStatus(TreeNode &)> TickFunctor