bt_factory.cpp
Go to the documentation of this file.
1 /* Copyright (C) 2018-2022 Davide Faconti, Eurecat - All Rights Reserved
2 *
3 * Permission is hereby granted, free of charge, to any person obtaining a copy of this software and associated documentation files (the "Software"),
4 * to deal in the Software without restriction, including without limitation the rights to use, copy, modify, merge, publish, distribute, sublicense,
5 * 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:
6 * The above copyright notice and this permission notice shall be included in all copies or substantial portions of the Software.
7 *
8 * THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY,
9 * 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,
10 * 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.
11 */
12 
13 #include <filesystem>
18 #include "wildcards/wildcards.hpp"
19 
20 #ifdef USING_ROS
21 #include <ros/package.h>
22 #endif
23 
24 namespace BT
25 {
26 
27 bool WildcardMatch(std::string const& str, StringView filter)
28 {
29  return wildcards::match(str, filter);
30 }
31 
33 {
34  std::unordered_map<std::string, NodeBuilder> builders;
35  std::unordered_map<std::string, TreeNodeManifest> manifests;
36  std::set<std::string> builtin_IDs;
37  std::unordered_map<std::string, Any> behavior_tree_definitions;
38  std::shared_ptr<std::unordered_map<std::string, int>> scripting_enums;
39  std::shared_ptr<BT::Parser> parser;
40  std::unordered_map<std::string, SubstitutionRule> substitution_rules;
41 };
42 
44 {
45  _p->parser = std::make_shared<XMLParser>(*this);
46  registerNodeType<FallbackNode>("Fallback");
47  registerNodeType<FallbackNode>("AsyncFallback", true);
48  registerNodeType<SequenceNode>("Sequence");
49  registerNodeType<SequenceNode>("AsyncSequence", true);
50  registerNodeType<SequenceWithMemory>("SequenceWithMemory");
51 
52 #ifdef USE_BTCPP3_OLD_NAMES
53  registerNodeType<SequenceWithMemory>("SequenceStar"); // backward compatibility
54 #endif
55 
56  registerNodeType<ParallelNode>("Parallel");
57  registerNodeType<ParallelAllNode>("ParallelAll");
58  registerNodeType<ReactiveSequence>("ReactiveSequence");
59  registerNodeType<ReactiveFallback>("ReactiveFallback");
60  registerNodeType<IfThenElseNode>("IfThenElse");
61  registerNodeType<WhileDoElseNode>("WhileDoElse");
62 
63  registerNodeType<InverterNode>("Inverter");
64 
65  registerNodeType<RetryNode>("RetryUntilSuccessful");
66  registerNodeType<KeepRunningUntilFailureNode>("KeepRunningUntilFailure");
67  registerNodeType<RepeatNode>("Repeat");
68  registerNodeType<TimeoutNode>("Timeout");
69  registerNodeType<DelayNode>("Delay");
70  registerNodeType<RunOnceNode>("RunOnce");
71 
72  registerNodeType<ForceSuccessNode>("ForceSuccess");
73  registerNodeType<ForceFailureNode>("ForceFailure");
74 
75  registerNodeType<AlwaysSuccessNode>("AlwaysSuccess");
76  registerNodeType<AlwaysFailureNode>("AlwaysFailure");
77  registerNodeType<ScriptNode>("Script");
78  registerNodeType<ScriptCondition>("ScriptCondition");
79  registerNodeType<SetBlackboardNode>("SetBlackboard");
80  registerNodeType<SleepNode>("Sleep");
81  registerNodeType<UnsetBlackboardNode>("UnsetBlackboard");
82 
83  registerNodeType<SubTreeNode>("SubTree");
84 
85  registerNodeType<PreconditionNode>("Precondition");
86 
87  registerNodeType<SwitchNode<2>>("Switch2");
88  registerNodeType<SwitchNode<3>>("Switch3");
89  registerNodeType<SwitchNode<4>>("Switch4");
90  registerNodeType<SwitchNode<5>>("Switch5");
91  registerNodeType<SwitchNode<6>>("Switch6");
92 
93  registerNodeType<LoopNode<int>>("LoopInt");
94  registerNodeType<LoopNode<bool>>("LoopBool");
95  registerNodeType<LoopNode<double>>("LoopDouble");
96  registerNodeType<LoopNode<std::string>>("LoopString");
97 
98  registerNodeType<EntryUpdatedAction>("WasEntryUpdated");
99  registerNodeType<EntryUpdatedDecorator>("SkipUnlessUpdated", NodeStatus::SKIPPED);
100  registerNodeType<EntryUpdatedDecorator>("WaitValueUpdate", NodeStatus::RUNNING);
101 
102  for(const auto& it : _p->builders)
103  {
104  _p->builtin_IDs.insert(it.first);
105  }
106 
107  _p->scripting_enums = std::make_shared<std::unordered_map<std::string, int>>();
108 }
109 
111 {}
112 
113 bool BehaviorTreeFactory::unregisterBuilder(const std::string& ID)
114 {
115  if(builtinNodes().count(ID))
116  {
117  throw LogicError("You can not remove the builtin registration ID [", ID, "]");
118  }
119  auto it = _p->builders.find(ID);
120  if(it == _p->builders.end())
121  {
122  return false;
123  }
124  _p->builders.erase(ID);
125  _p->manifests.erase(ID);
126  return true;
127 }
128 
130  const NodeBuilder& builder)
131 {
132  auto it = _p->builders.find(manifest.registration_ID);
133  if(it != _p->builders.end())
134  {
135  throw BehaviorTreeException("ID [", manifest.registration_ID, "] already registered");
136  }
137 
138  _p->builders.insert({ manifest.registration_ID, builder });
139  _p->manifests.insert({ manifest.registration_ID, manifest });
140 }
141 
143  const std::string& ID, const SimpleConditionNode::TickFunctor& tick_functor,
144  PortsList ports)
145 {
146  NodeBuilder builder = [tick_functor, ID](const std::string& name,
147  const NodeConfig& config) {
148  return std::make_unique<SimpleConditionNode>(name, tick_functor, config);
149  };
150 
151  TreeNodeManifest manifest = { NodeType::CONDITION, ID, std::move(ports), {} };
152  registerBuilder(manifest, builder);
153 }
154 
156  const std::string& ID, const SimpleActionNode::TickFunctor& tick_functor,
157  PortsList ports)
158 {
159  NodeBuilder builder = [tick_functor, ID](const std::string& name,
160  const NodeConfig& config) {
161  return std::make_unique<SimpleActionNode>(name, tick_functor, config);
162  };
163 
164  TreeNodeManifest manifest = { NodeType::ACTION, ID, std::move(ports), {} };
165  registerBuilder(manifest, builder);
166 }
167 
169  const std::string& ID, const SimpleDecoratorNode::TickFunctor& tick_functor,
170  PortsList ports)
171 {
172  NodeBuilder builder = [tick_functor, ID](const std::string& name,
173  const NodeConfig& config) {
174  return std::make_unique<SimpleDecoratorNode>(name, tick_functor, config);
175  };
176 
177  TreeNodeManifest manifest = { NodeType::DECORATOR, ID, std::move(ports), {} };
178  registerBuilder(manifest, builder);
179 }
180 
181 void BehaviorTreeFactory::registerFromPlugin(const std::string& file_path)
182 {
183  BT::SharedLibrary loader;
184  loader.load(file_path);
185  typedef void (*Func)(BehaviorTreeFactory&);
186 
187  if(loader.hasSymbol(PLUGIN_SYMBOL))
188  {
189  Func func = (Func)loader.getSymbol(PLUGIN_SYMBOL);
190  func(*this);
191  }
192  else
193  {
194  std::cout << "ERROR loading library [" << file_path << "]: can't find symbol ["
195  << PLUGIN_SYMBOL << "]" << std::endl;
196  }
197 }
198 
199 #ifdef USING_ROS
200 
201 #ifdef _WIN32
202 const char os_pathsep(';'); // NOLINT
203 #else
204 const char os_pathsep(':'); // NOLINT
205 #endif
206 
207 // This function is a copy from the one in class_loader_imp.hpp in ROS pluginlib
208 // package, licensed under BSD.
209 // https://github.com/ros/pluginlib
210 std::vector<std::string> getCatkinLibraryPaths()
211 {
212  std::vector<std::string> lib_paths;
213  const char* env = std::getenv("CMAKE_PREFIX_PATH");
214  if(env)
215  {
216  const std::string env_catkin_prefix_paths(env);
217  std::vector<BT::StringView> catkin_prefix_paths =
218  splitString(env_catkin_prefix_paths, os_pathsep);
219  for(BT::StringView catkin_prefix_path : catkin_prefix_paths)
220  {
221  std::filesystem::path path(static_cast<std::string>(catkin_prefix_path));
222  std::filesystem::path lib("lib");
223  lib_paths.push_back((path / lib).string());
224  }
225  }
226  return lib_paths;
227 }
228 
230 {
231  std::vector<std::string> plugins;
232  ros::package::getPlugins("behaviortree_cpp", "bt_lib_plugin", plugins, true);
233  std::vector<std::string> catkin_lib_paths = getCatkinLibraryPaths();
234 
235  for(const auto& plugin : plugins)
236  {
237  auto filename = std::filesystem::path(plugin + BT::SharedLibrary::suffix());
238  for(const auto& lib_path : catkin_lib_paths)
239  {
240  const auto full_path = std::filesystem::path(lib_path) / filename;
241  if(std::filesystem::exists(full_path))
242  {
243  std::cout << "Registering ROS plugins from " << full_path.string() << std::endl;
244  registerFromPlugin(full_path.string());
245  break;
246  }
247  }
248  }
249 }
250 #else
251 
253 {
254  throw RuntimeError("Using attribute [ros_pkg] in <include>, but this library was "
255  "compiled without ROS support. Recompile the BehaviorTree.CPP "
256  "using catkin");
257 }
258 #endif
259 
261  const std::filesystem::path& filename)
262 {
263  _p->parser->loadFromFile(filename);
264 }
265 
267 {
268  _p->parser->loadFromText(xml_text);
269 }
270 
271 std::vector<std::string> BehaviorTreeFactory::registeredBehaviorTrees() const
272 {
273  return _p->parser->registeredBehaviorTrees();
274 }
275 
277 {
278  _p->parser->clearInternalState();
279 }
280 
282  const std::string& name, const std::string& ID, const NodeConfig& config) const
283 {
284  auto idNotFound = [this, ID] {
285  std::cerr << ID << " not included in this list:" << std::endl;
286  for(const auto& builder_it : _p->builders)
287  {
288  std::cerr << builder_it.first << std::endl;
289  }
290  throw RuntimeError("BehaviorTreeFactory: ID [", ID, "] not registered");
291  };
292 
293  auto it_manifest = _p->manifests.find(ID);
294  if(it_manifest == _p->manifests.end())
295  {
296  idNotFound();
297  }
298 
299  std::unique_ptr<TreeNode> node;
300 
301  bool substituted = false;
302  for(const auto& [filter, rule] : _p->substitution_rules)
303  {
304  if(filter == name || filter == ID || wildcards::match(config.path, filter))
305  {
306  // first case: the rule is simply a string with the name of the
307  // node to create instead
308  if(const auto substituted_ID = std::get_if<std::string>(&rule))
309  {
310  auto it_builder = _p->builders.find(*substituted_ID);
311  if(it_builder != _p->builders.end())
312  {
313  auto& builder = it_builder->second;
314  node = builder(name, config);
315  }
316  else
317  {
318  throw RuntimeError("Substituted Node ID [", *substituted_ID, "] not found");
319  }
320  substituted = true;
321  break;
322  }
323  else if(const auto test_config = std::get_if<TestNodeConfig>(&rule))
324  {
325  // second case, the varian is a TestNodeConfig
326  auto test_node = new TestNode(name, config, *test_config);
327  node.reset(test_node);
328  substituted = true;
329  break;
330  }
331  }
332  }
333 
334  // No substitution rule applied: default behavior
335  if(!substituted)
336  {
337  auto it_builder = _p->builders.find(ID);
338  if(it_builder == _p->builders.end())
339  {
340  idNotFound();
341  }
342  auto& builder = it_builder->second;
343  node = builder(name, config);
344  }
345 
346  node->setRegistrationID(ID);
347  node->config().enums = _p->scripting_enums;
348 
349  auto AssignConditions = [](auto& conditions, auto& executors) {
350  for(const auto& [cond_id, script] : conditions)
351  {
352  if(auto executor = ParseScript(script))
353  {
354  executors[size_t(cond_id)] = executor.value();
355  }
356  else
357  {
358  throw LogicError("Error in the script \"", script, "\"\n", executor.error());
359  }
360  }
361  };
362  AssignConditions(config.pre_conditions, node->preConditionsScripts());
363  AssignConditions(config.post_conditions, node->postConditionsScripts());
364 
365  return node;
366 }
367 
368 const std::unordered_map<std::string, NodeBuilder>& BehaviorTreeFactory::builders() const
369 {
370  return _p->builders;
371 }
372 
373 const std::unordered_map<std::string, TreeNodeManifest>&
375 {
376  return _p->manifests;
377 }
378 
379 const std::set<std::string>& BehaviorTreeFactory::builtinNodes() const
380 {
381  return _p->builtin_IDs;
382 }
383 
385  Blackboard::Ptr blackboard)
386 {
387  if(!_p->parser->registeredBehaviorTrees().empty())
388  {
389  std::cout << "WARNING: You executed BehaviorTreeFactory::createTreeFromText "
390  "after registerBehaviorTreeFrom[File/Text].\n"
391  "This is NOT, probably, what you want to do.\n"
392  "You should probably use BehaviorTreeFactory::createTree, instead"
393  << std::endl;
394  }
395  XMLParser parser(*this);
396  parser.loadFromText(text);
397  auto tree = parser.instantiateTree(blackboard);
398  tree.manifests = this->manifests();
399  return tree;
400 }
401 
402 Tree BehaviorTreeFactory::createTreeFromFile(const std::filesystem::path& file_path,
403  Blackboard::Ptr blackboard)
404 {
405  if(!_p->parser->registeredBehaviorTrees().empty())
406  {
407  std::cout << "WARNING: You executed BehaviorTreeFactory::createTreeFromFile "
408  "after registerBehaviorTreeFrom[File/Text].\n"
409  "This is NOT, probably, what you want to do.\n"
410  "You should probably use BehaviorTreeFactory::createTree, instead"
411  << std::endl;
412  }
413 
414  XMLParser parser(*this);
415  parser.loadFromFile(file_path);
416  auto tree = parser.instantiateTree(blackboard);
417  tree.manifests = this->manifests();
418  return tree;
419 }
420 
421 Tree BehaviorTreeFactory::createTree(const std::string& tree_name,
422  Blackboard::Ptr blackboard)
423 {
424  auto tree = _p->parser->instantiateTree(blackboard, tree_name);
425  tree.manifests = this->manifests();
426  return tree;
427 }
428 
429 void BehaviorTreeFactory::addMetadataToManifest(const std::string& node_id,
430  const KeyValueVector& metadata)
431 {
432  auto it = _p->manifests.find(node_id);
433  if(it == _p->manifests.end())
434  {
435  throw std::runtime_error("addMetadataToManifest: wrong ID");
436  }
437  it->second.metadata = metadata;
438 }
439 
441 {
442  const auto str = std::string(name);
443  auto it = _p->scripting_enums->find(str);
444  if(it == _p->scripting_enums->end())
445  {
446  _p->scripting_enums->insert({ str, value });
447  }
448  else
449  {
450  if(it->second != value)
451  {
452  throw LogicError(
453  StrCat("Registering the enum [", name, "] twice with different values, first ",
454  std::to_string(it->second), " and later ", std::to_string(value)));
455  }
456  }
457 }
458 
460 {
461  _p->substitution_rules.clear();
462 }
463 
465 {
466  _p->substitution_rules[std::string(filter)] = rule;
467 }
468 
470 {
471  auto const json = nlohmann::json::parse(json_text);
472 
473  std::unordered_map<std::string, TestNodeConfig> configs;
474 
475  auto test_configs = json.at("TestNodeConfigs");
476  for(auto const& [name, test_config] : test_configs.items())
477  {
478  auto& config = configs[name];
479 
480  auto return_status = test_config.at("return_status").get<std::string>();
481  config.return_status = convertFromString<NodeStatus>(return_status);
482  if(test_config.contains("async_delay"))
483  {
484  config.async_delay =
485  std::chrono::milliseconds(test_config["async_delay"].get<int>());
486  }
487  if(test_config.contains("post_script"))
488  {
489  config.post_script = test_config["post_script"].get<std::string>();
490  }
491  if(test_config.contains("success_script"))
492  {
493  config.success_script = test_config["success_script"].get<std::string>();
494  }
495  if(test_config.contains("failure_script"))
496  {
497  config.failure_script = test_config["failure_script"].get<std::string>();
498  }
499  }
500 
501  auto substitutions = json.at("SubstitutionRules");
502  for(auto const& [node_name, test] : substitutions.items())
503  {
504  auto test_name = test.get<std::string>();
505  auto it = configs.find(test_name);
506  if(it == configs.end())
507  {
508  addSubstitutionRule(node_name, test_name);
509  }
510  else
511  {
512  addSubstitutionRule(node_name, it->second);
513  }
514  }
515 }
516 
517 const std::unordered_map<std::string, BehaviorTreeFactory::SubstitutionRule>&
519 {
520  return _p->substitution_rules;
521 }
522 
524 {}
525 
527 {
528  wake_up_ = std::make_shared<WakeUpSignal>();
529  for(auto& subtree : subtrees)
530  {
531  for(auto& node : subtree->nodes)
532  {
533  node->setWakeUpInstance(wake_up_);
534  }
535  }
536 }
537 
539 {
540  if(!rootNode())
541  {
542  return;
543  }
544  // the halt should propagate to all the node if the nodes
545  // have been implemented correctly
546  rootNode()->haltNode();
547 
548  //but, just in case.... this should be no-op
549  auto visitor = [](BT::TreeNode* node) { node->haltNode(); };
551 
552  rootNode()->resetStatus();
553 }
554 
556 {
557  if(subtrees.empty())
558  {
559  return nullptr;
560  }
561  auto& subtree_nodes = subtrees.front()->nodes;
562  return subtree_nodes.empty() ? nullptr : subtree_nodes.front().get();
563 }
564 
565 bool Tree::sleep(std::chrono::system_clock::duration timeout)
566 {
567  return wake_up_->waitFor(
568  std::chrono::duration_cast<std::chrono::milliseconds>(timeout));
569 }
570 
572 {
573  haltTree();
574 }
575 
577 {
578  return tickRoot(EXACTLY_ONCE, std::chrono::milliseconds(0));
579 }
580 
582 {
583  return tickRoot(ONCE_UNLESS_WOKEN_UP, std::chrono::milliseconds(0));
584 }
585 
586 NodeStatus Tree::tickWhileRunning(std::chrono::milliseconds sleep_time)
587 {
588  return tickRoot(WHILE_RUNNING, sleep_time);
589 }
590 
592 {
593  if(subtrees.size() > 0)
594  {
595  return subtrees.front()->blackboard;
596  }
597  return {};
598 }
599 
600 void Tree::applyVisitor(const std::function<void(const TreeNode*)>& visitor) const
601 {
602  BT::applyRecursiveVisitor(static_cast<const TreeNode*>(rootNode()), visitor);
603 }
604 
605 void Tree::applyVisitor(const std::function<void(TreeNode*)>& visitor)
606 {
607  BT::applyRecursiveVisitor(static_cast<TreeNode*>(rootNode()), visitor);
608 }
609 
610 uint16_t Tree::getUID()
611 {
612  auto uid = ++uid_counter_;
613  return uid;
614 }
615 
616 NodeStatus Tree::tickRoot(TickOption opt, std::chrono::milliseconds sleep_time)
617 {
618  NodeStatus status = NodeStatus::IDLE;
619 
620  if(!wake_up_)
621  {
622  initialize();
623  }
624 
625  if(!rootNode())
626  {
627  throw RuntimeError("Empty Tree");
628  }
629 
630  while(status == NodeStatus::IDLE ||
631  (opt == TickOption::WHILE_RUNNING && status == NodeStatus::RUNNING))
632  {
633  status = rootNode()->executeTick();
634 
635  // Inner loop. The previous tick might have triggered the wake-up
636  // in this case, unless TickOption::EXACTLY_ONCE, we tick again
637  while(opt != TickOption::EXACTLY_ONCE && status == NodeStatus::RUNNING &&
638  wake_up_->waitFor(std::chrono::milliseconds(0)))
639  {
640  status = rootNode()->executeTick();
641  }
642 
643  if(isStatusCompleted(status))
644  {
645  rootNode()->resetStatus();
646  }
647  if(status == NodeStatus::RUNNING && sleep_time.count() > 0)
648  {
649  sleep(std::chrono::milliseconds(sleep_time));
650  }
651  }
652 
653  return status;
654 }
655 
656 void BlackboardRestore(const std::vector<Blackboard::Ptr>& backup, Tree& tree)
657 {
658  assert(backup.size() == tree.subtrees.size());
659  for(size_t i = 0; i < tree.subtrees.size(); i++)
660  {
661  backup[i]->cloneInto(*(tree.subtrees[i]->blackboard));
662  }
663 }
664 
665 std::vector<Blackboard::Ptr> BlackboardBackup(const Tree& tree)
666 {
667  std::vector<Blackboard::Ptr> bb;
668  bb.reserve(tree.subtrees.size());
669  for(const auto& sub : tree.subtrees)
670  {
671  bb.push_back(BT::Blackboard::create());
672  sub->blackboard->cloneInto(*bb.back());
673  }
674  return bb;
675 }
676 
678 {
679  nlohmann::json out;
680  for(const auto& subtree : tree.subtrees)
681  {
682  nlohmann::json json_sub;
683  auto sub_name = subtree->instance_name;
684  if(sub_name.empty())
685  {
686  sub_name = subtree->tree_ID;
687  }
688  out[sub_name] = ExportBlackboardToJSON(*subtree->blackboard);
689  }
690  return out;
691 }
692 
694 {
695  if(json.size() != tree.subtrees.size())
696  {
697  throw std::runtime_error("Number of blackboards don't match:");
698  }
699 
700  size_t index = 0;
701  for(auto& [key, array] : json.items())
702  {
703  auto& subtree = tree.subtrees.at(index++);
704  ImportBlackboardFromJSON(array, *subtree->blackboard);
705  }
706 }
707 
708 } // namespace BT
BT
Definition: ex01_wrap_legacy.cpp:29
BT::SharedLibrary::load
void load(const std::string &path, int flags=0)
Definition: shared_library_UNIX.cpp:14
BT::BehaviorTreeFactory::builtinNodes
const std::set< std::string > & builtinNodes() const
List of builtin IDs.
Definition: bt_factory.cpp:379
BT::BlackboardRestore
void BlackboardRestore(const std::vector< Blackboard::Ptr > &backup, BT::Tree &tree)
BlackboardRestore uses Blackboard::cloneInto to restore all the blackboards of the tree.
Definition: bt_factory.cpp:656
BT::ParseScript
Expected< ScriptFunction > ParseScript(const std::string &script)
Definition: script_parser.cpp:14
BT::BehaviorTreeException
Definition: exceptions.h:23
BT::Tree::ONCE_UNLESS_WOKEN_UP
@ ONCE_UNLESS_WOKEN_UP
Definition: bt_factory.h:191
BT::Tree::getUID
uint16_t getUID()
Definition: bt_factory.cpp:610
BT::NodeConfig::pre_conditions
std::map< PreCond, std::string > pre_conditions
Definition: tree_node.h:110
BT::BehaviorTreeFactory::registeredBehaviorTrees
std::vector< std::string > registeredBehaviorTrees() const
Definition: bt_factory.cpp:271
BT::XMLParser::loadFromText
void loadFromText(const std::string &xml_text, bool add_includes=true) override
Definition: xml_parsing.cpp:171
BT::BehaviorTreeFactory::createTree
Tree createTree(const std::string &tree_name, Blackboard::Ptr blackboard=Blackboard::create())
Definition: bt_factory.cpp:421
BT::BehaviorTreeFactory::PImpl::parser
std::shared_ptr< BT::Parser > parser
Definition: bt_factory.cpp:39
BT::BehaviorTreeFactory::unregisterBuilder
bool unregisterBuilder(const std::string &ID)
Remove a registered ID.
Definition: bt_factory.cpp:113
BT::SimpleDecoratorNode::TickFunctor
std::function< NodeStatus(NodeStatus, TreeNode &)> TickFunctor
Definition: decorator_node.h:55
BT::NodeType::DECORATOR
@ DECORATOR
BT::NodeType::CONDITION
@ CONDITION
BT::BehaviorTreeFactory::substitutionRules
const std::unordered_map< std::string, SubstitutionRule > & substitutionRules() const
substitutionRules return the current substitution rules.
Definition: bt_factory.cpp:518
BT::TreeNode::executeTick
virtual BT::NodeStatus executeTick()
The method that should be used to invoke tick() and setStatus();.
Definition: tree_node.cpp:71
BT::BehaviorTreeFactory::_p
std::unique_ptr< PImpl > _p
Definition: bt_factory.h:504
BT::BehaviorTreeFactory::BehaviorTreeFactory
BehaviorTreeFactory()
Definition: bt_factory.cpp:43
BT::StringView
std::string_view StringView
Definition: basic_types.h:59
BT::NodeConfig::path
std::string path
Definition: tree_node.h:108
BT::BehaviorTreeFactory::loadSubstitutionRuleFromJSON
void loadSubstitutionRuleFromJSON(const std::string &json_text)
loadSubstitutionRuleFromJSON will parse a JSON file to create a set of substitution rules....
Definition: bt_factory.cpp:469
wildcards.hpp
BT::BehaviorTreeFactory::registerFromPlugin
void registerFromPlugin(const std::string &file_path)
registerFromPlugin load a shared library and execute the function BT_REGISTER_NODES (see macro).
Definition: bt_factory.cpp:181
BT::TreeNode
Abstract base class for Behavior Tree Nodes.
Definition: tree_node.h:131
BT::BehaviorTreeFactory::PImpl::builtin_IDs
std::set< std::string > builtin_IDs
Definition: bt_factory.cpp:36
BT::Tree
Struct used to store a tree. If this object goes out of scope, the tree is destroyed.
Definition: bt_factory.h:91
BT::ImportBlackboardFromJSON
void ImportBlackboardFromJSON(const nlohmann::json &json, Blackboard &blackboard)
ImportBlackboardFromJSON will append elements to the blackboard, using the values parsed from the JSO...
Definition: blackboard.cpp:284
BT::Tree::manifests
std::unordered_map< std::string, TreeNodeManifest > manifests
Definition: bt_factory.h:105
BT::BehaviorTreeFactory::addMetadataToManifest
void addMetadataToManifest(const std::string &node_id, const KeyValueVector &metadata)
Definition: bt_factory.cpp:429
BT::Tree::tickOnce
NodeStatus tickOnce()
by default, tickOnce() sends a single tick, BUT as long as there is at least one node of the tree inv...
Definition: bt_factory.cpp:581
manifest
string manifest
bt_factory.h
basic_json
namespace for Niels Lohmann
Definition: json.hpp:3411
BT::SharedLibrary::getSymbol
void * getSymbol(const std::string &name)
Definition: shared_library.cpp:9
BT::PLUGIN_SYMBOL
constexpr const char * PLUGIN_SYMBOL
Definition: bt_factory.h:83
BT::BehaviorTreeFactory::clearRegisteredBehaviorTrees
void clearRegisteredBehaviorTrees()
Clear previously-registered behavior trees.
Definition: bt_factory.cpp:276
BT::LogicError
Definition: exceptions.h:45
BT::Tree::Tree
Tree()
Definition: bt_factory.cpp:523
BT::BehaviorTreeFactory::clearSubstitutionRules
void clearSubstitutionRules()
Definition: bt_factory.cpp:459
wildcards::match
constexpr full_match_result< const_iterator_t< Sequence >, const_iterator_t< Pattern > > match(Sequence &&sequence, Pattern &&pattern, const cards< container_item_t< Pattern >> &c=cards< container_item_t< Pattern >>(), const EqualTo &equal_to=EqualTo())
Definition: wildcards.hpp:1606
BT::BehaviorTreeFactory::registerScriptingEnum
void registerScriptingEnum(StringView name, int value)
Add an Enum to the scripting language. For instance if you do:
Definition: bt_factory.cpp:440
BT::BehaviorTreeFactory::PImpl::scripting_enums
std::shared_ptr< std::unordered_map< std::string, int > > scripting_enums
Definition: bt_factory.cpp:38
BT::ExportBlackboardToJSON
nlohmann::json ExportBlackboardToJSON(const Blackboard &blackboard)
ExportBlackboardToJSON will create a JSON that contains the current values of the blackboard....
Definition: blackboard.cpp:267
BT::BehaviorTreeFactory::manifests
const std::unordered_map< std::string, TreeNodeManifest > & manifests() const
Manifests of all the registered TreeNodes.
Definition: bt_factory.cpp:374
BT::WildcardMatch
bool WildcardMatch(const std::string &str, StringView filter)
Definition: bt_factory.cpp:27
detail::void
j template void())
Definition: json.hpp:4893
BT::SharedLibrary::suffix
static std::string suffix()
Definition: shared_library_UNIX.cpp:74
BT::BehaviorTreeFactory::instantiateTreeNode
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.
Definition: bt_factory.cpp:281
BT::Tree::tickWhileRunning
NodeStatus tickWhileRunning(std::chrono::milliseconds sleep_time=std::chrono::milliseconds(10))
Definition: bt_factory.cpp:586
BT::Blackboard::Ptr
std::shared_ptr< Blackboard > Ptr
Definition: blackboard.h:35
BT::PortsList
std::unordered_map< std::string, PortInfo > PortsList
Definition: basic_types.h:587
BT::BehaviorTreeFactory::registerBuilder
void registerBuilder(const TreeNodeManifest &manifest, const NodeBuilder &builder)
Definition: bt_factory.cpp:129
lexy::count
constexpr auto count
Sink that counts all arguments.
Definition: fold.hpp:88
BT::Tree::sleep
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...
Definition: bt_factory.cpp:565
json_text
static const char * json_text
Definition: gtest_substitution.cpp:6
BT::Tree::rootNode
TreeNode * rootNode() const
Definition: bt_factory.cpp:555
lexy::parse
constexpr auto parse(const Input &input, const ErrorCallback &callback)
Parses the production into a value, invoking the callback on error.
Definition: parse.hpp:171
BT::BehaviorTreeFactory::PImpl::builders
std::unordered_map< std::string, NodeBuilder > builders
Definition: bt_factory.cpp:34
BT::Tree::tickRoot
NodeStatus tickRoot(TickOption opt, std::chrono::milliseconds sleep_time)
Definition: bt_factory.cpp:616
BT::NodeStatus::SKIPPED
@ SKIPPED
BT::NodeType::ACTION
@ ACTION
BT::Tree::~Tree
~Tree()
Definition: bt_factory.cpp:571
BT::BehaviorTreeFactory::createTreeFromText
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 ...
Definition: bt_factory.cpp:384
ros::package::getPlugins
ROSLIB_DECL void getPlugins(const std::string &name, const std::string &attribute, std::vector< std::pair< std::string, std::string > > &exports, bool force_recrawl=false)
BT::BehaviorTreeFactory::PImpl::behavior_tree_definitions
std::unordered_map< std::string, Any > behavior_tree_definitions
Definition: bt_factory.cpp:37
BT::BehaviorTreeFactory::~BehaviorTreeFactory
~BehaviorTreeFactory()
Definition: bt_factory.cpp:110
BT::Tree::initialize
void initialize()
Definition: bt_factory.cpp:526
BT::Tree::tickExactlyOnce
NodeStatus tickExactlyOnce()
Definition: bt_factory.cpp:576
BT::XMLParser::instantiateTree
Tree instantiateTree(const Blackboard::Ptr &root_blackboard, std::string main_tree_to_execute={}) override
Definition: xml_parsing.cpp:594
BT::TreeNode::haltNode
void haltNode()
Definition: tree_node.cpp:148
BT::BehaviorTreeFactory::PImpl
Definition: bt_factory.cpp:32
BT::Tree::wake_up_
std::shared_ptr< WakeUpSignal > wake_up_
Definition: bt_factory.h:186
BT::RuntimeError
Definition: exceptions.h:58
BT::TreeNodeManifest
This information is used mostly by the XMLParser.
Definition: tree_node.h:35
BT::SharedLibrary
Definition: shared_library.h:47
BT::ExportTreeToJSON
nlohmann::json ExportTreeToJSON(const BT::Tree &tree)
ExportTreeToJSON it calls ExportBlackboardToJSON for all the blackboards in the tree.
Definition: bt_factory.cpp:677
BT::splitString
std::vector< StringView > splitString(const StringView &strToSplit, char delimeter)
Definition: basic_types.cpp:349
BT::ImportTreeFromJSON
void ImportTreeFromJSON(const nlohmann::json &json, BT::Tree &tree)
ImportTreeFromJSON it calls ImportBlackboardFromJSON for all the blackboards in the tree.
Definition: bt_factory.cpp:693
to_string
NLOHMANN_BASIC_JSON_TPL_DECLARATION std::string to_string(const NLOHMANN_BASIC_JSON_TPL &j)
user-defined to_string function for JSON values
Definition: json.hpp:24456
xml_parsing.h
BT::BehaviorTreeFactory::PImpl::manifests
std::unordered_map< std::string, TreeNodeManifest > manifests
Definition: bt_factory.cpp:35
BT::applyRecursiveVisitor
void applyRecursiveVisitor(const TreeNode *root_node, const std::function< void(const TreeNode *)> &visitor)
Definition: behavior_tree.cpp:18
BT::BehaviorTreeFactory
The BehaviorTreeFactory is used to create instances of a TreeNode at run-time.
Definition: bt_factory.h:209
BT::Tree::WHILE_RUNNING
@ WHILE_RUNNING
Definition: bt_factory.h:192
BT::KeyValueVector
std::vector< std::pair< std::string, std::string > > KeyValueVector
Definition: basic_types.h:66
package.h
BT::StrCat
std::string StrCat()
Definition: strcat.hpp:46
BT::BehaviorTreeFactory::createTreeFromFile
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...
Definition: bt_factory.cpp:402
BT::Blackboard::create
static Blackboard::Ptr create(Blackboard::Ptr parent={})
Definition: blackboard.h:63
BT::BehaviorTreeFactory::builders
const std::unordered_map< std::string, NodeBuilder > & builders() const
All the builders. Made available mostly for debug purposes.
Definition: bt_factory.cpp:368
BT::TestNode
The TestNode is a Node that can be configure to:
Definition: test_node.h:64
BT::Tree::subtrees
std::vector< Subtree::Ptr > subtrees
Definition: bt_factory.h:104
BT::XMLParser::loadFromFile
void loadFromFile(const std::filesystem::path &filename, bool add_includes=true) override
Definition: xml_parsing.cpp:159
json.hpp
BT::NodeStatus::RUNNING
@ RUNNING
BT::Tree::haltTree
void haltTree()
Definition: bt_factory.cpp:538
BT::BehaviorTreeFactory::registerSimpleDecorator
void registerSimpleDecorator(const std::string &ID, const SimpleDecoratorNode::TickFunctor &tick_functor, PortsList ports={})
registerSimpleDecorator help you register nodes of type SimpleDecoratorNode.
Definition: bt_factory.cpp:168
BT::BlackboardBackup
std::vector< Blackboard::Ptr > BlackboardBackup(const BT::Tree &tree)
BlackboardBackup uses Blackboard::cloneInto to backup all the blackboards of the tree.
Definition: bt_factory.cpp:665
BT::isStatusCompleted
bool isStatusCompleted(const NodeStatus &status)
Definition: basic_types.h:47
BT::SharedLibrary::hasSymbol
bool hasSymbol(const std::string &name)
Definition: shared_library.cpp:18
BT::BehaviorTreeFactory::registerBehaviorTreeFromFile
void registerBehaviorTreeFromFile(const std::filesystem::path &filename)
registerBehaviorTreeFromFile. Load the definition of an entire behavior tree, but don't instantiate i...
Definition: bt_factory.cpp:260
BT::BehaviorTreeFactory::SubstitutionRule
std::variant< std::string, TestNodeConfig > SubstitutionRule
Definition: bt_factory.h:473
BT::NodeConfig::post_conditions
std::map< PostCond, std::string > post_conditions
Definition: tree_node.h:111
json
basic_json<> json
default specialization
Definition: json.hpp:3422
BT::TreeNode::resetStatus
void resetStatus()
Set the status to IDLE.
Definition: tree_node.cpp:268
BT::BehaviorTreeFactory::registerBehaviorTreeFromText
void registerBehaviorTreeFromText(const std::string &xml_text)
Definition: bt_factory.cpp:266
BT::SimpleConditionNode::TickFunctor
std::function< NodeStatus(TreeNode &)> TickFunctor
Definition: condition_node.h:53
basic_json::get
auto get() const noexcept(noexcept(std::declval< const basic_json_t & >().template get_impl< ValueType >(detail::priority_tag< 4 > {}))) -> decltype(std::declval< const basic_json_t & >().template get_impl< ValueType >(detail::priority_tag< 4 >
get a (pointer) value (explicit)
Definition: json.hpp:21046
BT::NodeStatus::IDLE
@ IDLE
BT::Tree::rootBlackboard
Blackboard::Ptr rootBlackboard()
Definition: bt_factory.cpp:591
BT::BehaviorTreeFactory::addSubstitutionRule
void addSubstitutionRule(StringView filter, SubstitutionRule rule)
addSubstitutionRule replace a node with another one when the tree is created. If the rule ia a string...
Definition: bt_factory.cpp:464
BT::Tree::TickOption
TickOption
Definition: bt_factory.h:188
lexyd::opt
constexpr auto opt(Rule)
Definition: option.hpp:81
BT::NodeBuilder
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)
Definition: bt_factory.h:31
BT::XMLParser
The XMLParser is a class used to read the model of a BehaviorTree from file or text and instantiate t...
Definition: xml_parsing.h:16
BT::NodeConfig
Definition: tree_node.h:82
BT::BehaviorTreeFactory::registerSimpleCondition
void registerSimpleCondition(const std::string &ID, const SimpleConditionNode::TickFunctor &tick_functor, PortsList ports={})
registerSimpleCondition help you register nodes of type SimpleConditionNode.
Definition: bt_factory.cpp:142
BT::convertFromString< NodeStatus >
NodeStatus convertFromString< NodeStatus >(StringView str)
Definition: basic_types.cpp:285
BT::BehaviorTreeFactory::PImpl::substitution_rules
std::unordered_map< std::string, SubstitutionRule > substitution_rules
Definition: bt_factory.cpp:40
xml_text
static const char * xml_text
Definition: ex01_wrap_legacy.cpp:52
shared_library.h
BT::Tree::EXACTLY_ONCE
@ EXACTLY_ONCE
Definition: bt_factory.h:190
BT::SimpleActionNode::TickFunctor
std::function< NodeStatus(TreeNode &)> TickFunctor
Definition: action_node.h:82
BT::BehaviorTreeFactory::registerFromROSPlugins
void registerFromROSPlugins()
registerFromROSPlugins finds all shared libraries that export ROS plugins for behaviortree_cpp,...
Definition: bt_factory.cpp:252
BT::NodeStatus
NodeStatus
Definition: basic_types.h:33
BT::Tree::applyVisitor
void applyVisitor(const std::function< void(const TreeNode *)> &visitor) const
Definition: bt_factory.cpp:600
basic_json::at
reference at(size_type idx)
access specified array element with bounds checking
Definition: json.hpp:21240
BT::BehaviorTreeFactory::registerSimpleAction
void registerSimpleAction(const std::string &ID, const SimpleActionNode::TickFunctor &tick_functor, PortsList ports={})
registerSimpleAction help you register nodes of type SimpleActionNode.
Definition: bt_factory.cpp:155
BT::Tree::uid_counter_
uint16_t uid_counter_
Definition: bt_factory.h:197


behaviortree_cpp_v4
Author(s): Davide Faconti
autogenerated on Wed Apr 16 2025 02:20:55