27 parser_ = std::make_shared<XMLParser>(*
this);
28 registerNodeType<FallbackNode>(
"Fallback");
29 registerNodeType<SequenceNode>(
"Sequence");
30 registerNodeType<SequenceStarNode>(
"SequenceStar");
31 registerNodeType<ParallelNode>(
"Parallel");
32 registerNodeType<ReactiveSequence>(
"ReactiveSequence");
33 registerNodeType<ReactiveFallback>(
"ReactiveFallback");
34 registerNodeType<IfThenElseNode>(
"IfThenElse");
35 registerNodeType<WhileDoElseNode>(
"WhileDoElse");
37 registerNodeType<InverterNode>(
"Inverter");
39 registerNodeType<RetryNode>(
"RetryUntilSuccessful");
40 registerNodeType<KeepRunningUntilFailureNode>(
"KeepRunningUntilFailure");
41 registerNodeType<RepeatNode>(
"Repeat");
42 registerNodeType<TimeoutNode<>>(
"Timeout");
43 registerNodeType<DelayNode>(
"Delay");
45 registerNodeType<ForceSuccessNode>(
"ForceSuccess");
46 registerNodeType<ForceFailureNode>(
"ForceFailure");
48 registerNodeType<AlwaysSuccessNode>(
"AlwaysSuccess");
49 registerNodeType<AlwaysFailureNode>(
"AlwaysFailure");
50 registerNodeType<SetBlackboard>(
"SetBlackboard");
52 registerNodeType<SubtreeNode>(
"SubTree");
53 registerNodeType<SubtreePlusNode>(
"SubTreePlus");
55 registerNodeType<BlackboardPreconditionNode<int>>(
"BlackboardCheckInt");
56 registerNodeType<BlackboardPreconditionNode<double>>(
"BlackboardCheckDouble");
57 registerNodeType<BlackboardPreconditionNode<std::string>>(
"BlackboardCheckString");
58 registerNodeType<BlackboardPreconditionNode<bool>>(
"BlackboardCheckBool");
60 registerNodeType<SwitchNode<2>>(
"Switch2");
61 registerNodeType<SwitchNode<3>>(
"Switch3");
62 registerNodeType<SwitchNode<4>>(
"Switch4");
63 registerNodeType<SwitchNode<5>>(
"Switch5");
64 registerNodeType<SwitchNode<6>>(
"Switch6");
67 registerNodeType<ManualSelectorNode>(
"ManualSelector");
79 throw LogicError(
"You can not remove the builtin registration ID [", ID,
"]");
108 NodeBuilder builder = [tick_functor, ID](
const std::string& name,
110 return std::make_unique<SimpleConditionNode>(name, tick_functor, config);
121 NodeBuilder builder = [tick_functor, ID](
const std::string& name,
123 return std::make_unique<SimpleActionNode>(name, tick_functor, config);
134 NodeBuilder builder = [tick_functor, ID](
const std::string& name,
136 return std::make_unique<SimpleDecoratorNode>(name, tick_functor, config);
146 loader.
load(file_path);
156 std::cout <<
"ERROR loading library [" << file_path <<
"]: can't find symbol ["
164 const char os_pathsep(
';');
166 const char os_pathsep(
':');
172 std::vector<std::string> getCatkinLibraryPaths()
174 std::vector<std::string> lib_paths;
175 const char* env = std::getenv(
"CMAKE_PREFIX_PATH");
178 const std::string env_catkin_prefix_paths(env);
179 std::vector<BT::StringView> catkin_prefix_paths =
183 filesystem::path
path(
static_cast<std::string
>(catkin_prefix_path));
184 filesystem::path lib(
"lib");
185 lib_paths.push_back((
path / lib).str());
193 std::vector<std::string> plugins;
195 std::vector<std::string> catkin_lib_paths = getCatkinLibraryPaths();
197 for (
const auto& plugin : plugins)
200 for (
const auto& lib_path : catkin_lib_paths)
202 const auto full_path = filesystem::path(lib_path) / filename;
203 if (full_path.exists())
205 std::cout <<
"Registering ROS plugins from " << full_path.str() << std::endl;
216 throw RuntimeError(
"Using attribute [ros_pkg] in <include>, but this library was "
218 "without ROS support. Recompile the BehaviorTree.CPP using "
225 parser_->loadFromFile(filename);
235 return parser_->registeredBehaviorTrees();
244 const std::string& name,
const std::string& ID,
const NodeConfiguration& config)
const
249 std::cerr << ID <<
" not included in this list:" << std::endl;
252 std::cerr << builder_it.first << std::endl;
254 throw RuntimeError(
"BehaviorTreeFactory: ID [", ID,
"] not registered");
257 std::unique_ptr<TreeNode> node = it->second(name, config);
258 node->setRegistrationID(ID);
267 const std::unordered_map<std::string, TreeNodeManifest>&
281 if(!
parser_->registeredBehaviorTrees().empty()) {
282 std::cout <<
"WARNING: You executed BehaviorTreeFactory::createTreeFromText "
283 "after registerBehaviorTreeFrom[File/Text].\n"
284 "This is NOTm probably, what you want to do.\n"
285 "You should probably use BehaviorTreeFactory::createTree, instead"
298 if(!
parser_->registeredBehaviorTrees().empty()) {
299 std::cout <<
"WARNING: You executed BehaviorTreeFactory::createTreeFromFile "
300 "after registerBehaviorTreeFrom[File/Text].\n"
301 "This is NOTm probably, what you want to do.\n"
302 "You should probably use BehaviorTreeFactory::createTree, instead"
316 auto tree =
parser_->instantiateTree(blackboard, tree_name);
322 const std::string& description)
327 throw std::runtime_error(
"addDescriptionToManifest: wrong ID");
329 it->second.description = description;