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  this->_p = std::move(other._p);
113 }
114 
116 {
117  this->_p = std::move(other._p);
118  return *this;
119 }
120 
122 {}
123 
124 bool BehaviorTreeFactory::unregisterBuilder(const std::string& ID)
125 {
126  if(builtinNodes().count(ID))
127  {
128  throw LogicError("You can not remove the builtin registration ID [", ID, "]");
129  }
130  auto it = _p->builders.find(ID);
131  if(it == _p->builders.end())
132  {
133  return false;
134  }
135  _p->builders.erase(ID);
136  _p->manifests.erase(ID);
137  return true;
138 }
139 
141  const NodeBuilder& builder)
142 {
143  auto it = _p->builders.find(manifest.registration_ID);
144  if(it != _p->builders.end())
145  {
146  throw BehaviorTreeException("ID [", manifest.registration_ID, "] already registered");
147  }
148 
149  _p->builders.insert({ manifest.registration_ID, builder });
150  _p->manifests.insert({ manifest.registration_ID, manifest });
151 }
152 
154  const std::string& ID, const SimpleConditionNode::TickFunctor& tick_functor,
155  PortsList ports)
156 {
157  NodeBuilder builder = [tick_functor, ID](const std::string& name,
158  const NodeConfig& config) {
159  return std::make_unique<SimpleConditionNode>(name, tick_functor, config);
160  };
161 
162  TreeNodeManifest manifest = { NodeType::CONDITION, ID, std::move(ports), {} };
163  registerBuilder(manifest, builder);
164 }
165 
167  const std::string& ID, const SimpleActionNode::TickFunctor& tick_functor,
168  PortsList ports)
169 {
170  NodeBuilder builder = [tick_functor, ID](const std::string& name,
171  const NodeConfig& config) {
172  return std::make_unique<SimpleActionNode>(name, tick_functor, config);
173  };
174 
175  TreeNodeManifest manifest = { NodeType::ACTION, ID, std::move(ports), {} };
176  registerBuilder(manifest, builder);
177 }
178 
180  const std::string& ID, const SimpleDecoratorNode::TickFunctor& tick_functor,
181  PortsList ports)
182 {
183  NodeBuilder builder = [tick_functor, ID](const std::string& name,
184  const NodeConfig& config) {
185  return std::make_unique<SimpleDecoratorNode>(name, tick_functor, config);
186  };
187 
188  TreeNodeManifest manifest = { NodeType::DECORATOR, ID, std::move(ports), {} };
189  registerBuilder(manifest, builder);
190 }
191 
192 void BehaviorTreeFactory::registerFromPlugin(const std::string& file_path)
193 {
194  BT::SharedLibrary loader;
195  loader.load(file_path);
196  typedef void (*Func)(BehaviorTreeFactory&);
197 
198  if(loader.hasSymbol(PLUGIN_SYMBOL))
199  {
200  Func func = (Func)loader.getSymbol(PLUGIN_SYMBOL);
201  func(*this);
202  }
203  else
204  {
205  std::cout << "ERROR loading library [" << file_path << "]: can't find symbol ["
206  << PLUGIN_SYMBOL << "]" << std::endl;
207  }
208 }
209 
210 #ifdef USING_ROS
211 
212 #ifdef _WIN32
213 const char os_pathsep(';'); // NOLINT
214 #else
215 const char os_pathsep(':'); // NOLINT
216 #endif
217 
218 // This function is a copy from the one in class_loader_imp.hpp in ROS pluginlib
219 // package, licensed under BSD.
220 // https://github.com/ros/pluginlib
221 std::vector<std::string> getCatkinLibraryPaths()
222 {
223  std::vector<std::string> lib_paths;
224  const char* env = std::getenv("CMAKE_PREFIX_PATH");
225  if(env)
226  {
227  const std::string env_catkin_prefix_paths(env);
228  std::vector<BT::StringView> catkin_prefix_paths =
229  splitString(env_catkin_prefix_paths, os_pathsep);
230  for(BT::StringView catkin_prefix_path : catkin_prefix_paths)
231  {
232  std::filesystem::path path(static_cast<std::string>(catkin_prefix_path));
233  std::filesystem::path lib("lib");
234  lib_paths.push_back((path / lib).string());
235  }
236  }
237  return lib_paths;
238 }
239 
241 {
242  std::vector<std::string> plugins;
243  ros::package::getPlugins("behaviortree_cpp", "bt_lib_plugin", plugins, true);
244  std::vector<std::string> catkin_lib_paths = getCatkinLibraryPaths();
245 
246  for(const auto& plugin : plugins)
247  {
248  auto filename = std::filesystem::path(plugin + BT::SharedLibrary::suffix());
249  for(const auto& lib_path : catkin_lib_paths)
250  {
251  const auto full_path = std::filesystem::path(lib_path) / filename;
252  if(std::filesystem::exists(full_path))
253  {
254  std::cout << "Registering ROS plugins from " << full_path.string() << std::endl;
255  registerFromPlugin(full_path.string());
256  break;
257  }
258  }
259  }
260 }
261 #else
262 
264 {
265  throw RuntimeError("Using attribute [ros_pkg] in <include>, but this library was "
266  "compiled without ROS support. Recompile the BehaviorTree.CPP "
267  "using catkin");
268 }
269 #endif
270 
272  const std::filesystem::path& filename)
273 {
274  _p->parser->loadFromFile(filename);
275 }
276 
278 {
279  _p->parser->loadFromText(xml_text);
280 }
281 
282 std::vector<std::string> BehaviorTreeFactory::registeredBehaviorTrees() const
283 {
284  return _p->parser->registeredBehaviorTrees();
285 }
286 
288 {
289  _p->parser->clearInternalState();
290 }
291 
293  const std::string& name, const std::string& ID, const NodeConfig& config) const
294 {
295  auto idNotFound = [this, ID] {
296  std::cerr << ID << " not included in this list:" << std::endl;
297  for(const auto& builder_it : _p->builders)
298  {
299  std::cerr << builder_it.first << std::endl;
300  }
301  throw RuntimeError("BehaviorTreeFactory: ID [", ID, "] not registered");
302  };
303 
304  auto it_manifest = _p->manifests.find(ID);
305  if(it_manifest == _p->manifests.end())
306  {
307  idNotFound();
308  }
309 
310  std::unique_ptr<TreeNode> node;
311 
312  bool substituted = false;
313  for(const auto& [filter, rule] : _p->substitution_rules)
314  {
315  if(filter == name || filter == ID || wildcards::match(config.path, filter))
316  {
317  // first case: the rule is simply a string with the name of the
318  // node to create instead
319  if(const auto substituted_ID = std::get_if<std::string>(&rule))
320  {
321  auto it_builder = _p->builders.find(*substituted_ID);
322  if(it_builder != _p->builders.end())
323  {
324  auto& builder = it_builder->second;
325  node = builder(name, config);
326  }
327  else
328  {
329  throw RuntimeError("Substituted Node ID [", *substituted_ID, "] not found");
330  }
331  substituted = true;
332  break;
333  }
334  else if(const auto test_config = std::get_if<TestNodeConfig>(&rule))
335  {
336  // second case, the varian is a TestNodeConfig
337  auto test_node = new TestNode(name, config, *test_config);
338  node.reset(test_node);
339  substituted = true;
340  break;
341  }
342  }
343  }
344 
345  // No substitution rule applied: default behavior
346  if(!substituted)
347  {
348  auto it_builder = _p->builders.find(ID);
349  if(it_builder == _p->builders.end())
350  {
351  idNotFound();
352  }
353  auto& builder = it_builder->second;
354  node = builder(name, config);
355  }
356 
357  node->setRegistrationID(ID);
358  node->config().enums = _p->scripting_enums;
359 
360  auto AssignConditions = [](auto& conditions, auto& executors) {
361  for(const auto& [cond_id, script] : conditions)
362  {
363  if(auto executor = ParseScript(script))
364  {
365  executors[size_t(cond_id)] = executor.value();
366  }
367  else
368  {
369  throw LogicError("Error in the script \"", script, "\"\n", executor.error());
370  }
371  }
372  };
373  AssignConditions(config.pre_conditions, node->preConditionsScripts());
374  AssignConditions(config.post_conditions, node->postConditionsScripts());
375 
376  return node;
377 }
378 
379 const std::unordered_map<std::string, NodeBuilder>& BehaviorTreeFactory::builders() const
380 {
381  return _p->builders;
382 }
383 
384 const std::unordered_map<std::string, TreeNodeManifest>&
386 {
387  return _p->manifests;
388 }
389 
390 const std::set<std::string>& BehaviorTreeFactory::builtinNodes() const
391 {
392  return _p->builtin_IDs;
393 }
394 
396  Blackboard::Ptr blackboard)
397 {
398  if(!_p->parser->registeredBehaviorTrees().empty())
399  {
400  std::cout << "WARNING: You executed BehaviorTreeFactory::createTreeFromText "
401  "after registerBehaviorTreeFrom[File/Text].\n"
402  "This is NOT, probably, what you want to do.\n"
403  "You should probably use BehaviorTreeFactory::createTree, instead"
404  << std::endl;
405  }
406  XMLParser parser(*this);
407  parser.loadFromText(text);
408  auto tree = parser.instantiateTree(blackboard);
409  tree.manifests = this->manifests();
410  return tree;
411 }
412 
413 Tree BehaviorTreeFactory::createTreeFromFile(const std::filesystem::path& file_path,
414  Blackboard::Ptr blackboard)
415 {
416  if(!_p->parser->registeredBehaviorTrees().empty())
417  {
418  std::cout << "WARNING: You executed BehaviorTreeFactory::createTreeFromFile "
419  "after registerBehaviorTreeFrom[File/Text].\n"
420  "This is NOT, probably, what you want to do.\n"
421  "You should probably use BehaviorTreeFactory::createTree, instead"
422  << std::endl;
423  }
424 
425  XMLParser parser(*this);
426  parser.loadFromFile(file_path);
427  auto tree = parser.instantiateTree(blackboard);
428  tree.manifests = this->manifests();
429  return tree;
430 }
431 
432 Tree BehaviorTreeFactory::createTree(const std::string& tree_name,
433  Blackboard::Ptr blackboard)
434 {
435  auto tree = _p->parser->instantiateTree(blackboard, tree_name);
436  tree.manifests = this->manifests();
437  return tree;
438 }
439 
440 void BehaviorTreeFactory::addMetadataToManifest(const std::string& node_id,
441  const KeyValueVector& metadata)
442 {
443  auto it = _p->manifests.find(node_id);
444  if(it == _p->manifests.end())
445  {
446  throw std::runtime_error("addMetadataToManifest: wrong ID");
447  }
448  it->second.metadata = metadata;
449 }
450 
452 {
453  const auto str = std::string(name);
454  auto it = _p->scripting_enums->find(str);
455  if(it == _p->scripting_enums->end())
456  {
457  _p->scripting_enums->insert({ str, value });
458  }
459  else
460  {
461  if(it->second != value)
462  {
463  throw LogicError(
464  StrCat("Registering the enum [", name, "] twice with different values, first ",
465  std::to_string(it->second), " and later ", std::to_string(value)));
466  }
467  }
468 }
469 
471 {
472  _p->substitution_rules.clear();
473 }
474 
476 {
477  _p->substitution_rules[std::string(filter)] = rule;
478 }
479 
481 {
482  auto const json = nlohmann::json::parse(json_text);
483 
484  std::unordered_map<std::string, TestNodeConfig> configs;
485 
486  auto test_configs = json.at("TestNodeConfigs");
487  for(auto const& [name, test_config] : test_configs.items())
488  {
489  auto& config = configs[name];
490 
491  auto return_status = test_config.at("return_status").get<std::string>();
492  config.return_status = convertFromString<NodeStatus>(return_status);
493  if(test_config.contains("async_delay"))
494  {
495  config.async_delay =
496  std::chrono::milliseconds(test_config["async_delay"].get<int>());
497  }
498  if(test_config.contains("post_script"))
499  {
500  config.post_script = test_config["post_script"].get<std::string>();
501  }
502  if(test_config.contains("success_script"))
503  {
504  config.success_script = test_config["success_script"].get<std::string>();
505  }
506  if(test_config.contains("failure_script"))
507  {
508  config.failure_script = test_config["failure_script"].get<std::string>();
509  }
510  }
511 
512  auto substitutions = json.at("SubstitutionRules");
513  for(auto const& [node_name, test] : substitutions.items())
514  {
515  auto test_name = test.get<std::string>();
516  auto it = configs.find(test_name);
517  if(it == configs.end())
518  {
519  addSubstitutionRule(node_name, test_name);
520  }
521  else
522  {
523  addSubstitutionRule(node_name, it->second);
524  }
525  }
526 }
527 
528 const std::unordered_map<std::string, BehaviorTreeFactory::SubstitutionRule>&
530 {
531  return _p->substitution_rules;
532 }
533 
535 {
536  subtrees = std::move(other.subtrees);
537  manifests = std::move(other.manifests);
538  wake_up_ = other.wake_up_;
539  return *this;
540 }
541 
543 {}
544 
545 Tree::Tree(Tree&& other)
546 {
547  (*this) = std::move(other);
548 }
549 
551 {
552  wake_up_ = std::make_shared<WakeUpSignal>();
553  for(auto& subtree : subtrees)
554  {
555  for(auto& node : subtree->nodes)
556  {
557  node->setWakeUpInstance(wake_up_);
558  }
559  }
560 }
561 
563 {
564  if(!rootNode())
565  {
566  return;
567  }
568  // the halt should propagate to all the node if the nodes
569  // have been implemented correctly
570  rootNode()->haltNode();
571 
572  //but, just in case.... this should be no-op
573  auto visitor = [](BT::TreeNode* node) { node->haltNode(); };
575 
576  rootNode()->resetStatus();
577 }
578 
580 {
581  if(subtrees.empty())
582  {
583  return nullptr;
584  }
585  auto& subtree_nodes = subtrees.front()->nodes;
586  return subtree_nodes.empty() ? nullptr : subtree_nodes.front().get();
587 }
588 
589 void Tree::sleep(std::chrono::system_clock::duration timeout)
590 {
591  wake_up_->waitFor(std::chrono::duration_cast<std::chrono::milliseconds>(timeout));
592 }
593 
595 {
596  haltTree();
597 }
598 
600 {
601  return tickRoot(EXACTLY_ONCE, std::chrono::milliseconds(0));
602 }
603 
605 {
606  return tickRoot(ONCE_UNLESS_WOKEN_UP, std::chrono::milliseconds(0));
607 }
608 
609 NodeStatus Tree::tickWhileRunning(std::chrono::milliseconds sleep_time)
610 {
611  return tickRoot(WHILE_RUNNING, sleep_time);
612 }
613 
615 {
616  if(subtrees.size() > 0)
617  {
618  return subtrees.front()->blackboard;
619  }
620  return {};
621 }
622 
623 void Tree::applyVisitor(const std::function<void(const TreeNode*)>& visitor)
624 {
625  BT::applyRecursiveVisitor(static_cast<const TreeNode*>(rootNode()), visitor);
626 }
627 
628 void Tree::applyVisitor(const std::function<void(TreeNode*)>& visitor)
629 {
630  BT::applyRecursiveVisitor(static_cast<TreeNode*>(rootNode()), visitor);
631 }
632 
633 uint16_t Tree::getUID()
634 {
635  auto uid = ++uid_counter_;
636  return uid;
637 }
638 
639 NodeStatus Tree::tickRoot(TickOption opt, std::chrono::milliseconds sleep_time)
640 {
641  NodeStatus status = NodeStatus::IDLE;
642 
643  if(!wake_up_)
644  {
645  initialize();
646  }
647 
648  if(!rootNode())
649  {
650  throw RuntimeError("Empty Tree");
651  }
652 
653  while(status == NodeStatus::IDLE ||
654  (opt == TickOption::WHILE_RUNNING && status == NodeStatus::RUNNING))
655  {
656  status = rootNode()->executeTick();
657 
658  // Inner loop. The previous tick might have triggered the wake-up
659  // in this case, unless TickOption::EXACTLY_ONCE, we tick again
660  while(opt != TickOption::EXACTLY_ONCE && status == NodeStatus::RUNNING &&
661  wake_up_->waitFor(std::chrono::milliseconds(0)))
662  {
663  status = rootNode()->executeTick();
664  }
665 
666  if(isStatusCompleted(status))
667  {
668  rootNode()->resetStatus();
669  }
670  if(status == NodeStatus::RUNNING && sleep_time.count() > 0)
671  {
672  sleep(std::chrono::milliseconds(sleep_time));
673  }
674  }
675 
676  return status;
677 }
678 
679 void BlackboardRestore(const std::vector<Blackboard::Ptr>& backup, Tree& tree)
680 {
681  assert(backup.size() == tree.subtrees.size());
682  for(size_t i = 0; i < tree.subtrees.size(); i++)
683  {
684  backup[i]->cloneInto(*(tree.subtrees[i]->blackboard));
685  }
686 }
687 
688 std::vector<Blackboard::Ptr> BlackboardBackup(const Tree& tree)
689 {
690  std::vector<Blackboard::Ptr> bb;
691  bb.reserve(tree.subtrees.size());
692  for(const auto& sub : tree.subtrees)
693  {
694  bb.push_back(BT::Blackboard::create());
695  sub->blackboard->cloneInto(*bb.back());
696  }
697  return bb;
698 }
699 
701 {
702  nlohmann::json out;
703  for(const auto& subtree : tree.subtrees)
704  {
705  nlohmann::json json_sub;
706  auto sub_name = subtree->instance_name;
707  if(sub_name.empty())
708  {
709  sub_name = subtree->tree_ID;
710  }
711  out[sub_name] = ExportBlackboardToJSON(*subtree->blackboard);
712  }
713  return out;
714 }
715 
717 {
718  if(json.size() != tree.subtrees.size())
719  {
720  throw std::runtime_error("Number of blackboards don't match:");
721  }
722 
723  size_t index = 0;
724  for(auto& [key, array] : json.items())
725  {
726  auto& subtree = tree.subtrees.at(index++);
727  ImportBlackboardFromJSON(array, *subtree->blackboard);
728  }
729 }
730 
731 } // 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:390
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:679
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:187
BT::Tree::getUID
uint16_t getUID()
Definition: bt_factory.cpp:633
BT::NodeConfig::pre_conditions
std::map< PreCond, std::string > pre_conditions
Definition: tree_node.h:97
BT::BehaviorTreeFactory::registeredBehaviorTrees
std::vector< std::string > registeredBehaviorTrees() const
Definition: bt_factory.cpp:282
BT::XMLParser::loadFromText
void loadFromText(const std::string &xml_text, bool add_includes=true) override
Definition: xml_parsing.cpp:164
BT::BehaviorTreeFactory::createTree
Tree createTree(const std::string &tree_name, Blackboard::Ptr blackboard=Blackboard::create())
Definition: bt_factory.cpp:432
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:124
BT::SimpleDecoratorNode::TickFunctor
std::function< NodeStatus(NodeStatus, TreeNode &)> TickFunctor
Definition: decorator_node.h:55
BT::Tree::operator=
Tree & operator=(const Tree &)=delete
BT::NodeType::DECORATOR
@ DECORATOR
BT::NodeType::CONDITION
@ CONDITION
BT::BehaviorTreeFactory::operator=
BehaviorTreeFactory & operator=(const BehaviorTreeFactory &other)=delete
BT::BehaviorTreeFactory::substitutionRules
const std::unordered_map< std::string, SubstitutionRule > & substitutionRules() const
substitutionRules return the current substitution rules.
Definition: bt_factory.cpp:529
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:500
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:95
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:480
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:192
BT::TreeNode
Abstract base class for Behavior Tree Nodes.
Definition: tree_node.h:118
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:280
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:440
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:604
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:287
BT::LogicError
Definition: exceptions.h:45
BT::Tree::Tree
Tree()
Definition: bt_factory.cpp:542
BT::BehaviorTreeFactory::clearSubstitutionRules
void clearSubstitutionRules()
Definition: bt_factory.cpp:470
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:451
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:263
BT::BehaviorTreeFactory::manifests
const std::unordered_map< std::string, TreeNodeManifest > & manifests() const
Manifests of all the registered TreeNodes.
Definition: bt_factory.cpp:385
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:292
BT::Tree::tickWhileRunning
NodeStatus tickWhileRunning(std::chrono::milliseconds sleep_time=std::chrono::milliseconds(10))
Definition: bt_factory.cpp:609
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:585
BT::BehaviorTreeFactory::registerBuilder
void registerBuilder(const TreeNodeManifest &manifest, const NodeBuilder &builder)
Definition: bt_factory.cpp:140
lexy::count
constexpr auto count
Sink that counts all arguments.
Definition: fold.hpp:88
json_text
static const char * json_text
Definition: gtest_substitution.cpp:6
BT::Tree::rootNode
TreeNode * rootNode() const
Definition: bt_factory.cpp:579
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:639
BT::NodeStatus::SKIPPED
@ SKIPPED
BT::NodeType::ACTION
@ ACTION
BT::Tree::~Tree
~Tree()
Definition: bt_factory.cpp:594
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:395
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:121
BT::Tree::initialize
void initialize()
Definition: bt_factory.cpp:550
BT::Tree::tickExactlyOnce
NodeStatus tickExactlyOnce()
Definition: bt_factory.cpp:599
BT::XMLParser::instantiateTree
Tree instantiateTree(const Blackboard::Ptr &root_blackboard, std::string main_tree_to_execute={}) override
Definition: xml_parsing.cpp:550
BT::Tree::sleep
void sleep(std::chrono::system_clock::duration timeout)
Definition: bt_factory.cpp:589
BT::TreeNode::haltNode
void haltNode()
Definition: tree_node.cpp:142
BT::BehaviorTreeFactory::PImpl
Definition: bt_factory.cpp:32
BT::Tree::wake_up_
std::shared_ptr< WakeUpSignal > wake_up_
Definition: bt_factory.h:182
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:700
BT::splitString
std::vector< StringView > splitString(const StringView &strToSplit, char delimeter)
Definition: basic_types.cpp:348
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:716
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:205
BT::Tree::WHILE_RUNNING
@ WHILE_RUNNING
Definition: bt_factory.h:188
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:413
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:379
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:152
json.hpp
BT::NodeStatus::RUNNING
@ RUNNING
BT::Tree::haltTree
void haltTree()
Definition: bt_factory.cpp:562
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:179
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:688
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:271
BT::BehaviorTreeFactory::SubstitutionRule
std::variant< std::string, TestNodeConfig > SubstitutionRule
Definition: bt_factory.h:469
BT::NodeConfig::post_conditions
std::map< PostCond, std::string > post_conditions
Definition: tree_node.h:98
json
basic_json<> json
default specialization
Definition: json.hpp:3422
BT::TreeNode::resetStatus
void resetStatus()
Set the status to IDLE.
Definition: tree_node.cpp:262
BT::BehaviorTreeFactory::registerBehaviorTreeFromText
void registerBehaviorTreeFromText(const std::string &xml_text)
Definition: bt_factory.cpp:277
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:614
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:475
BT::Tree::TickOption
TickOption
Definition: bt_factory.h:184
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:73
BT::Tree::applyVisitor
void applyVisitor(const std::function< void(const TreeNode *)> &visitor)
Definition: bt_factory.cpp:623
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:153
BT::convertFromString< NodeStatus >
NodeStatus convertFromString< NodeStatus >(StringView str)
Definition: basic_types.cpp:284
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:186
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:263
BT::NodeStatus
NodeStatus
Definition: basic_types.h:33
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:166
BT::Tree::uid_counter_
uint16_t uid_counter_
Definition: bt_factory.h:193


behaviortree_cpp_v4
Author(s): Davide Faconti
autogenerated on Fri Jun 28 2024 02:20:07