xml_parsing.cpp
Go to the documentation of this file.
1 /* Copyright (C) 2018-2020 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 <functional>
14 #include <list>
15 
16 #if defined(__linux) || defined(__linux__)
17 #pragma GCC diagnostic push
18 #pragma GCC diagnostic ignored "-Wattributes"
19 #endif
20 
21 #ifdef _MSC_VER
22 #pragma warning(disable : 4996) // do not complain about sprintf
23 #endif
24 
25 #include <map>
27 #include "tinyxml2/tinyxml2.h"
28 #include "filesystem/path.h"
29 
30 #ifdef USING_ROS
31 #include <ros/package.h>
32 #endif
33 
34 #ifdef USING_ROS2
35 #include <ament_index_cpp/get_package_share_directory.hpp>
36 #endif
37 
40 
41 namespace BT
42 {
43 using namespace tinyxml2;
44 
45 auto StrEqual = [](const char* str1, const char* str2) -> bool {
46  return strcmp(str1, str2) == 0;
47 };
48 
50 {
51  TreeNode::Ptr createNodeFromXML(const XMLElement* element,
52  const Blackboard::Ptr& blackboard,
53  const TreeNode::Ptr& node_parent);
54 
55  void recursivelyCreateTree(const std::string& tree_ID, Tree& output_tree,
56  Blackboard::Ptr blackboard,
57  const TreeNode::Ptr& root_parent);
58 
59  void getPortsRecursively(const XMLElement* element,
60  std::vector<std::string>& output_ports);
61 
62  void loadDocImpl(tinyxml2::XMLDocument* doc, bool add_includes);
63 
64  std::list<std::unique_ptr<tinyxml2::XMLDocument> > opened_documents;
65  std::map<std::string, const XMLElement*> tree_roots;
66 
68 
69  filesystem::path current_path;
70 
72 
73  explicit Pimpl(const BehaviorTreeFactory& fact) :
74  factory(fact), current_path(filesystem::path::getcwd()), suffix_count(0)
75  {}
76 
77  void clear()
78  {
79  suffix_count = 0;
80  current_path = filesystem::path::getcwd();
81  opened_documents.clear();
82  tree_roots.clear();
83  }
84 };
85 
86 #if defined(__linux) || defined(__linux__)
87 #pragma GCC diagnostic pop
88 #endif
89 
90 XMLParser::XMLParser(const BehaviorTreeFactory& factory) : _p(new Pimpl(factory))
91 {}
92 
94 {
95  delete _p;
96 }
97 
98 void XMLParser::loadFromFile(const std::string& filename, bool add_includes)
99 {
100  _p->opened_documents.emplace_back(new tinyxml2::XMLDocument());
101 
102  tinyxml2::XMLDocument* doc = _p->opened_documents.back().get();
103  doc->LoadFile(filename.c_str());
104 
105  filesystem::path file_path(filename);
106  _p->current_path = file_path.parent_path().make_absolute();
107 
108  _p->loadDocImpl(doc, add_includes);
109 }
110 
111 void XMLParser::loadFromText(const std::string& xml_text, bool add_includes)
112 {
113  _p->opened_documents.emplace_back(new tinyxml2::XMLDocument());
114 
115  tinyxml2::XMLDocument* doc = _p->opened_documents.back().get();
116  doc->Parse(xml_text.c_str(), xml_text.size());
117 
118  _p->loadDocImpl(doc, add_includes);
119 }
120 
121 std::vector<std::string> XMLParser::registeredBehaviorTrees() const
122 {
123  std::vector<std::string> out;
124  for (const auto& it : _p->tree_roots)
125  {
126  out.push_back(it.first);
127  }
128  return out;
129 }
130 
132 {
133  if (doc->Error())
134  {
135  char buffer[200];
136  sprintf(buffer, "Error parsing the XML: %s", doc->ErrorName());
137  throw RuntimeError(buffer);
138  }
139 
140  const XMLElement* xml_root = doc->RootElement();
141 
142  // recursively include other files
143  for (auto include_node = xml_root->FirstChildElement("include");
144  include_node != nullptr; include_node = include_node->NextSiblingElement("includ"
145  "e"))
146  {
147  if (!add_includes)
148  {
149  break;
150  }
151 
152  filesystem::path file_path(include_node->Attribute("path"));
153  const char* ros_pkg_relative_path = include_node->Attribute("ros_pkg");
154 
155  if (ros_pkg_relative_path)
156  {
157  if (file_path.is_absolute())
158  {
159  std::cout << "WARNING: <include path=\"...\"> contains an absolute "
160  "path.\n"
161  << "Attribute [ros_pkg] will be ignored." << std::endl;
162  }
163  else
164  {
165  std::string ros_pkg_path;
166 #ifdef USING_ROS
167  ros_pkg_path = ros::package::getPath(ros_pkg_relative_path);
168  file_path = filesystem::path(ros_pkg_path) / file_path;
169 #elif defined USING_ROS2
170  ros_pkg_path =
171  ament_index_cpp::get_package_share_directory(ros_pkg_relative_path);
172  file_path = filesystem::path(ros_pkg_path) / file_path;
173 #else
174  throw RuntimeError("Using attribute [ros_pkg] in <include>, but this "
175  "library was "
176  "compiled "
177  "without ROS support. Recompile the BehaviorTree.CPP "
178  "using "
179  "catkin");
180 #endif
181  }
182  }
183 
184  if (!file_path.is_absolute())
185  {
186  file_path = current_path / file_path;
187  }
188 
189  opened_documents.emplace_back(new tinyxml2::XMLDocument());
190  tinyxml2::XMLDocument* next_doc = opened_documents.back().get();
191 
192  // change current path to the included file for handling additional relative paths
193  const filesystem::path previous_path = current_path;
194  current_path = file_path.parent_path().make_absolute();
195 
196  next_doc->LoadFile(file_path.str().c_str());
197  loadDocImpl(next_doc, add_includes);
198 
199  // reset current path to the previous value
200  current_path = previous_path;
201  }
202 
203  // Collect the names of all nodes registered with the behavior tree factory
204  std::unordered_map<std::string, BT::NodeType> registered_nodes;
205  for (const auto& it : factory.manifests())
206  {
207  registered_nodes.insert({it.first, it.second.type});
208  }
209 
210  XMLPrinter printer;
211  doc->Print(&printer);
212  auto xml_text = std::string(printer.CStr(), size_t(printer.CStrSize() - 1));
213 
214  // Verify the validity of the XML before adding any behavior trees to the parser's list of registered trees
215  VerifyXML(xml_text, registered_nodes);
216 
217  // Register each BehaviorTree within the XML
218  for (auto bt_node = xml_root->FirstChildElement("BehaviorTree"); bt_node != nullptr;
219  bt_node = bt_node->NextSiblingElement("BehaviorTree"))
220  {
221  std::string tree_name;
222  if (bt_node->Attribute("ID"))
223  {
224  tree_name = bt_node->Attribute("ID");
225  }
226  else
227  {
228  tree_name = "BehaviorTree_" + std::to_string(suffix_count++);
229  }
230 
231  tree_roots.insert({tree_name, bt_node});
232  }
233 }
234 
235 void VerifyXML(const std::string& xml_text,
236  const std::unordered_map<std::string, BT::NodeType>& registered_nodes)
237 {
239  auto xml_error = doc.Parse(xml_text.c_str(), xml_text.size());
240  if (xml_error)
241  {
242  char buffer[200];
243  sprintf(buffer, "Error parsing the XML: %s", doc.ErrorName());
244  throw RuntimeError(buffer);
245  }
246 
247  //-------- Helper functions (lambdas) -----------------
248  auto ThrowError = [&](int line_num, const std::string& text) {
249  char buffer[256];
250  sprintf(buffer, "Error at line %d: -> %s", line_num, text.c_str());
251  throw RuntimeError(buffer);
252  };
253 
254  auto ChildrenCount = [](const XMLElement* parent_node) {
255  int count = 0;
256  for (auto node = parent_node->FirstChildElement(); node != nullptr;
257  node = node->NextSiblingElement())
258  {
259  count++;
260  }
261  return count;
262  };
263  //-----------------------------
264 
265  const XMLElement* xml_root = doc.RootElement();
266 
267  if (!xml_root || !StrEqual(xml_root->Name(), "root"))
268  {
269  throw RuntimeError("The XML must have a root node called <root>");
270  }
271  //-------------------------------------------------
272  auto models_root = xml_root->FirstChildElement("TreeNodesModel");
273  auto meta_sibling =
274  models_root ? models_root->NextSiblingElement("TreeNodesModel") : nullptr;
275 
276  if (meta_sibling)
277  {
278  ThrowError(meta_sibling->GetLineNum(), " Only a single node <TreeNodesModel> is "
279  "supported");
280  }
281  if (models_root)
282  {
283  // not having a MetaModel is not an error. But consider that the
284  // Graphical editor needs it.
285  for (auto node = xml_root->FirstChildElement(); node != nullptr;
286  node = node->NextSiblingElement())
287  {
288  const char* name = node->Name();
289  if (StrEqual(name, "Action") || StrEqual(name, "Decorator") ||
290  StrEqual(name, "SubTree") || StrEqual(name, "Condition") ||
291  StrEqual(name, "Control"))
292  {
293  const char* ID = node->Attribute("ID");
294  if (!ID)
295  {
296  ThrowError(node->GetLineNum(), "Error at line %d: -> The attribute "
297  "[ID] is "
298  "mandatory");
299  }
300  }
301  }
302  }
303  //-------------------------------------------------
304 
305  // function to be called recursively
306  std::function<void(const XMLElement*)> recursiveStep;
307 
308  recursiveStep = [&](const XMLElement* node) {
309  const int children_count = ChildrenCount(node);
310  const char* name = node->Name();
311  if (StrEqual(name, "Decorator"))
312  {
313  if (children_count != 1)
314  {
315  ThrowError(node->GetLineNum(), "The node <Decorator> must have exactly 1 "
316  "child");
317  }
318  if (!node->Attribute("ID"))
319  {
320  ThrowError(node->GetLineNum(), "The node <Decorator> must have the "
321  "attribute [ID]");
322  }
323  }
324  else if (StrEqual(name, "Action"))
325  {
326  if (children_count != 0)
327  {
328  ThrowError(node->GetLineNum(), "The node <Action> must not have any "
329  "child");
330  }
331  if (!node->Attribute("ID"))
332  {
333  ThrowError(node->GetLineNum(), "The node <Action> must have the "
334  "attribute [ID]");
335  }
336  }
337  else if (StrEqual(name, "Condition"))
338  {
339  if (children_count != 0)
340  {
341  ThrowError(node->GetLineNum(), "The node <Condition> must not have any "
342  "child");
343  }
344  if (!node->Attribute("ID"))
345  {
346  ThrowError(node->GetLineNum(), "The node <Condition> must have the "
347  "attribute [ID]");
348  }
349  }
350  else if (StrEqual(name, "Control"))
351  {
352  if (children_count == 0)
353  {
354  ThrowError(node->GetLineNum(), "The node <Control> must have at least 1 "
355  "child");
356  }
357  if (!node->Attribute("ID"))
358  {
359  ThrowError(node->GetLineNum(), "The node <Control> must have the "
360  "attribute [ID]");
361  }
362  }
363  else if (StrEqual(name, "Sequence") || StrEqual(name, "SequenceStar") ||
364  StrEqual(name, "Fallback"))
365  {
366  if (children_count == 0)
367  {
368  ThrowError(node->GetLineNum(), "A Control node must have at least 1 "
369  "child");
370  }
371  }
372  else if (StrEqual(name, "SubTree"))
373  {
374  auto child = node->FirstChildElement();
375 
376  if (child)
377  {
378  if (StrEqual(child->Name(), "remap"))
379  {
380  ThrowError(node->GetLineNum(), "<remap> was deprecated");
381  }
382  else
383  {
384  ThrowError(node->GetLineNum(), "<SubTree> should not have any child");
385  }
386  }
387 
388  if (!node->Attribute("ID"))
389  {
390  ThrowError(node->GetLineNum(), "The node <SubTree> must have the "
391  "attribute [ID]");
392  }
393  }
394  else if (StrEqual(name, "BehaviorTree"))
395  {
396  if (children_count != 1)
397  {
398  ThrowError(node->GetLineNum(), "The node <BehaviorTree> must have exactly 1 "
399  "child");
400  }
401  }
402  else
403  {
404  // search in the factory and the list of subtrees
405  const auto search = registered_nodes.find(name);
406  bool found = (search != registered_nodes.end());
407  if (!found)
408  {
409  ThrowError(node->GetLineNum(), std::string("Node not recognized: ") + name);
410  }
411 
412  if (search->second == NodeType::DECORATOR)
413  {
414  if (children_count != 1)
415  {
416  ThrowError(node->GetLineNum(),
417  std::string("The node <") + name + "> must have exactly 1 child");
418  }
419  }
420  }
421  //recursion
422  if (StrEqual(name, "SubTree") == false)
423  {
424  for (auto child = node->FirstChildElement(); child != nullptr;
425  child = child->NextSiblingElement())
426  {
427  recursiveStep(child);
428  }
429  }
430  };
431 
432  for (auto bt_root = xml_root->FirstChildElement("BehaviorTree"); bt_root != nullptr;
433  bt_root = bt_root->NextSiblingElement("BehaviorTree"))
434  {
435  recursiveStep(bt_root);
436  }
437 }
438 
440  std::string main_tree_to_execute)
441 {
442  Tree output_tree;
443  std::string main_tree_ID = main_tree_to_execute;
444 
445  // use the main_tree_to_execute argument if it was provided by the user
446  // or the one in the FIRST document opened
447  if (main_tree_ID.empty())
448  {
449  XMLElement* first_xml_root = _p->opened_documents.front()->RootElement();
450 
451  if (auto main_tree_attribute = first_xml_root->Attribute("main_tree_to_execute"))
452  {
453  main_tree_ID = main_tree_attribute;
454  }
455  else if (_p->tree_roots.size() == 1)
456  {
457  // special case: there is only one registered BT.
458  main_tree_ID = _p->tree_roots.begin()->first;
459  }
460  else
461  {
462  throw RuntimeError("[main_tree_to_execute] was not specified correctly");
463  }
464  }
465 
466  //--------------------------------------
467  if (!root_blackboard)
468  {
469  throw RuntimeError("XMLParser::instantiateTree needs a non-empty "
470  "root_blackboard");
471  }
472  // first blackboard
473  output_tree.blackboard_stack.push_back(root_blackboard);
474 
475  _p->recursivelyCreateTree(main_tree_ID, output_tree, root_blackboard, TreeNode::Ptr());
476  output_tree.initialize();
477  return output_tree;
478 }
479 
481 {
482  _p->clear();
483 }
484 
486  const Blackboard::Ptr& blackboard,
487  const TreeNode::Ptr& node_parent)
488 {
489  const std::string element_name = element->Name();
490  std::string ID;
491  std::string instance_name;
492 
493  // Actions and Decorators have their own ID
494  if (element_name == "Action" || element_name == "Decorator" ||
495  element_name == "Condition" || element_name == "Control")
496  {
497  ID = element->Attribute("ID");
498  }
499  else
500  {
501  ID = element_name;
502  }
503 
504  const char* attr_alias = element->Attribute("name");
505  if (attr_alias)
506  {
507  instance_name = attr_alias;
508  }
509  else
510  {
511  instance_name = ID;
512  }
513 
514  PortsRemapping port_remap;
515 
516  if (element_name == "SubTree" || element_name == "SubTreePlus")
517  {
518  instance_name = element->Attribute("ID");
519  }
520  else
521  {
522  // do this only if it NOT a Subtree
523  for (const XMLAttribute* att = element->FirstAttribute(); att; att = att->Next())
524  {
525  const std::string attribute_name = att->Name();
526  if (!IsReservedPortname(attribute_name))
527  {
528  port_remap[attribute_name] = att->Value();
529  }
530  }
531  }
532  NodeConfiguration config;
533  config.blackboard = blackboard;
534 
535  //---------------------------------------------
536  TreeNode::Ptr child_node;
537 
538  if (factory.builders().count(ID) != 0)
539  {
540  const auto& manifest = factory.manifests().at(ID);
541 
542  //Check that name in remapping can be found in the manifest
543  for (const auto& remap_it : port_remap)
544  {
545  if (manifest.ports.count(remap_it.first) == 0)
546  {
547  throw RuntimeError("Possible typo? In the XML, you tried to remap port "
548  "\"",
549  remap_it.first, "\" in node [", ID, " / ", instance_name,
550  "], but the manifest of this node does not contain a "
551  "port with "
552  "this name.");
553  }
554  }
555 
556  // Initialize the ports in the BB to set the type
557  for (const auto& port_it : manifest.ports)
558  {
559  const std::string& port_name = port_it.first;
560  const auto& port_info = port_it.second;
561 
562  auto remap_it = port_remap.find(port_name);
563  if (remap_it == port_remap.end())
564  {
565  continue;
566  }
567  StringView param_value = remap_it->second;
568 
569  if (auto param_res = TreeNode::getRemappedKey(port_name, param_value))
570  {
571  // port_key will contain the key to find the entry in the blackboard
572  const auto port_key = static_cast<std::string>(param_res.value());
573 
574  // if the entry already exists, check that the type is the same
575  if (auto prev_info = blackboard->portInfo(port_key))
576  {
577  bool const port_type_mismatch = (prev_info->isStronglyTyped() &&
578  port_info.isStronglyTyped() &&
579  *prev_info->type() != *port_info.type());
580 
581  // special case related to convertFromString
582  bool const string_input = ( prev_info->type() &&
583  *prev_info->type() == typeid(std::string));
584 
585  if (port_type_mismatch && !string_input)
586  {
587  blackboard->debugMessage();
588 
589  throw RuntimeError("The creation of the tree failed because the port [",
590  port_key, "] was initially created with type [",
591  demangle(prev_info->type()), "] and, later type [",
592  demangle(port_info.type()), "] was used somewhere else.");
593  }
594  }
595  else
596  {
597  // not found, insert for the first time.
598  blackboard->createEntry(port_key, port_info);
599  }
600  }
601  }
602 
603  // use manifest to initialize NodeConfiguration
604  for (const auto& remap_it : port_remap)
605  {
606  const auto& port_name = remap_it.first;
607  auto port_it = manifest.ports.find(port_name);
608  if (port_it != manifest.ports.end())
609  {
610  auto direction = port_it->second.direction();
611  if (direction != PortDirection::OUTPUT)
612  {
613  config.input_ports.insert(remap_it);
614  }
615  if (direction != PortDirection::INPUT)
616  {
617  config.output_ports.insert(remap_it);
618  }
619  }
620  }
621 
622  // use default value if available for empty ports. Only inputs
623  for (const auto& port_it : manifest.ports)
624  {
625  const std::string& port_name = port_it.first;
626  const PortInfo& port_info = port_it.second;
627 
628  auto direction = port_info.direction();
629  if (direction != PortDirection::OUTPUT &&
630  config.input_ports.count(port_name) == 0 &&
631  port_info.defaultValue().empty() == false)
632  {
633  config.input_ports.insert({port_name, port_info.defaultValue()});
634  }
635  }
636 
637  child_node = factory.instantiateTreeNode(instance_name, ID, config);
638  }
639  else if (tree_roots.count(ID) != 0)
640  {
641  child_node = std::make_unique<SubtreeNode>(instance_name);
642  }
643  else
644  {
645  throw RuntimeError(ID, " is not a registered node, nor a Subtree");
646  }
647 
648  if (node_parent)
649  {
650  if (auto control_parent = dynamic_cast<ControlNode*>(node_parent.get()))
651  {
652  control_parent->addChild(child_node.get());
653  }
654  if (auto decorator_parent = dynamic_cast<DecoratorNode*>(node_parent.get()))
655  {
656  decorator_parent->setChild(child_node.get());
657  }
658  }
659  return child_node;
660 }
661 
662 void BT::XMLParser::Pimpl::recursivelyCreateTree(const std::string& tree_ID,
663  Tree& output_tree,
664  Blackboard::Ptr blackboard,
665  const TreeNode::Ptr& root_parent)
666 {
667  std::function<void(const TreeNode::Ptr&, const XMLElement*)> recursiveStep;
668 
669  recursiveStep = [&](const TreeNode::Ptr& parent, const XMLElement* element) {
670  // create the node
671  auto node = createNodeFromXML(element, blackboard, parent);
672  output_tree.nodes.push_back(node);
673 
674  if (node->type() == NodeType::SUBTREE)
675  {
676  if (dynamic_cast<const SubtreeNode*>(node.get()))
677  {
678  bool is_isolated = true;
679 
680  for (const XMLAttribute* attr = element->FirstAttribute(); attr != nullptr;
681  attr = attr->Next())
682  {
683  if (StrEqual(attr->Name(), "__shared_blackboard"))
684  {
685  is_isolated = !convertFromString<bool>(attr->Value());
686  break;
687  }
688  }
689 
690  if (!is_isolated)
691  {
692  recursivelyCreateTree(node->name(), output_tree, blackboard, node);
693  }
694  else
695  {
696  // Creating an isolated
697  auto new_bb = Blackboard::create(blackboard);
698 
699  for (const XMLAttribute* attr = element->FirstAttribute(); attr != nullptr;
700  attr = attr->Next())
701  {
702  if (!IsReservedPortname(attr->Name()))
703  {
704  new_bb->addSubtreeRemapping(attr->Name(), attr->Value());
705  }
706  }
707  output_tree.blackboard_stack.emplace_back(new_bb);
708  recursivelyCreateTree(node->name(), output_tree, new_bb, node);
709  }
710  }
711  else if (dynamic_cast<const SubtreePlusNode*>(node.get()))
712  {
713  auto new_bb = Blackboard::create(blackboard);
714  output_tree.blackboard_stack.emplace_back(new_bb);
715  std::set<StringView> mapped_keys;
716 
717  for (const XMLAttribute* attr = element->FirstAttribute(); attr != nullptr;
718  attr = attr->Next())
719  {
720  const char* attr_name = attr->Name();
721  const char* attr_value = attr->Value();
722 
723  if (IsReservedPortname(attr->Name()))
724  {
725  continue;
726  }
727  if (StrEqual(attr_name, "__autoremap"))
728  {
729  bool do_autoremap = convertFromString<bool>(attr_value);
730  new_bb->enableAutoRemapping(do_autoremap);
731  continue;
732  }
733 
734  if (TreeNode::isBlackboardPointer(attr_value))
735  {
736  // do remapping
737  StringView port_name = TreeNode::stripBlackboardPointer(attr_value);
738  new_bb->addSubtreeRemapping(attr_name, port_name);
739  mapped_keys.insert(attr_name);
740  }
741  else
742  {
743  // constant string: just set that constant value into the BB
744  new_bb->set(attr_name, static_cast<std::string>(attr_value));
745  mapped_keys.insert(attr_name);
746  }
747  }
748 
749  recursivelyCreateTree(node->name(), output_tree, new_bb, node);
750  }
751  }
752  else
753  {
754  for (auto child_element = element->FirstChildElement(); child_element;
755  child_element = child_element->NextSiblingElement())
756  {
757  recursiveStep(node, child_element);
758  }
759  }
760  };
761 
762  auto it = tree_roots.find(tree_ID);
763  if (it == tree_roots.end())
764  {
765  throw std::runtime_error(std::string("Can't find a tree with name: ") + tree_ID);
766  }
767 
768  auto root_element = it->second->FirstChildElement();
769 
770  // start recursion
771  recursiveStep(root_parent, root_element);
772 }
773 
775  std::vector<std::string>& output_ports)
776 {
777  for (const XMLAttribute* attr = element->FirstAttribute(); attr != nullptr;
778  attr = attr->Next())
779  {
780  const char* attr_name = attr->Name();
781  const char* attr_value = attr->Value();
782  if (!IsReservedPortname(attr_name) &&
783  TreeNode::isBlackboardPointer(attr_value))
784  {
785  auto port_name = TreeNode::stripBlackboardPointer(attr_value);
786  output_ports.push_back(static_cast<std::string>(port_name));
787  }
788  }
789 
790  for (auto child_element = element->FirstChildElement(); child_element;
791  child_element = child_element->NextSiblingElement())
792  {
793  getPortsRecursively(child_element, output_ports);
794  }
795 }
796 
797 std::string writeTreeNodesModelXML(const BehaviorTreeFactory& factory,
798  bool include_builtin)
799 {
800  XMLDocument doc;
801 
802  XMLElement* rootXML = doc.NewElement("root");
803  doc.InsertFirstChild(rootXML);
804 
805  XMLElement* model_root = doc.NewElement("TreeNodesModel");
806  rootXML->InsertEndChild(model_root);
807 
808  std::set<std::string> ordered_names;
809 
810  for (auto& model_it : factory.manifests())
811  {
812  const auto& registration_ID = model_it.first;
813  if (!include_builtin && factory.builtinNodes().count(registration_ID) != 0)
814  {
815  continue;
816  }
817  ordered_names.insert(registration_ID);
818  }
819 
820  for (auto& registration_ID : ordered_names)
821  {
822  const auto& model = factory.manifests().at(registration_ID);
823 
824  XMLElement* element = doc.NewElement(toStr(model.type).c_str());
825  element->SetAttribute("ID", model.registration_ID.c_str());
826 
827  std::vector<std::string> ordered_ports;
830  for (int d = 0; d < 3; d++)
831  {
832  std::set<std::string> port_names;
833  for (auto& port : model.ports)
834  {
835  const auto& port_name = port.first;
836  const auto& port_info = port.second;
837  if (port_info.direction() == directions[d])
838  {
839  port_names.insert(port_name);
840  }
841  }
842  for (auto& port : port_names)
843  {
844  ordered_ports.push_back(port);
845  }
846  }
847 
848  for (const auto& port_name : ordered_ports)
849  {
850  const auto& port_info = model.ports.at(port_name);
851 
852  XMLElement* port_element = nullptr;
853  switch (port_info.direction())
854  {
856  port_element = doc.NewElement("input_port");
857  break;
859  port_element = doc.NewElement("output_port");
860  break;
862  port_element = doc.NewElement("inout_port");
863  break;
864  }
865 
866  port_element->SetAttribute("name", port_name.c_str());
867  if (port_info.type())
868  {
869  port_element->SetAttribute("type", BT::demangle(port_info.type()).c_str());
870  }
871  if (!port_info.defaultValue().empty())
872  {
873  port_element->SetAttribute("default", port_info.defaultValue().c_str());
874  }
875 
876  if (!port_info.description().empty())
877  {
878  port_element->SetText(port_info.description().c_str());
879  }
880  element->InsertEndChild(port_element);
881  }
882 
883  if (!model.description.empty())
884  {
885  element->SetAttribute("description", model.registration_ID.c_str());
886  }
887 
888  model_root->InsertEndChild(element);
889  }
890 
891  XMLPrinter printer;
892  doc.Print(&printer);
893  return std::string(printer.CStr(), size_t(printer.CStrSize() - 1));
894 }
895 
896 Tree buildTreeFromText(const BehaviorTreeFactory& factory, const std::string& text,
897  const Blackboard::Ptr& blackboard)
898 {
899  XMLParser parser(factory);
900  parser.loadFromText(text);
901  return parser.instantiateTree(blackboard);
902 }
903 
904 Tree buildTreeFromFile(const BehaviorTreeFactory& factory, const std::string& filename,
905  const Blackboard::Ptr& blackboard)
906 {
907  XMLParser parser(factory);
908  parser.loadFromFile(filename);
909  return parser.instantiateTree(blackboard);
910 }
911 
912 } // namespace BT
BT::XMLParser::Pimpl::getPortsRecursively
void getPortsRecursively(const XMLElement *element, std::vector< std::string > &output_ports)
Definition: xml_parsing.cpp:774
BT::PortInfo
Definition: basic_types.h:225
BT
Definition: ex01_wrap_legacy.cpp:29
BT::BehaviorTreeFactory::builtinNodes
const std::set< std::string > & builtinNodes() const
List of builtin IDs.
Definition: bt_factory.cpp:273
path.h
BT::demangle
std::string demangle(char const *name)
Definition: demangle_util.h:72
BT::XMLParser::Pimpl::Pimpl
Pimpl(const BehaviorTreeFactory &fact)
Definition: xml_parsing.cpp:73
BT::XMLParser::Pimpl::createNodeFromXML
TreeNode::Ptr createNodeFromXML(const XMLElement *element, const Blackboard::Ptr &blackboard, const TreeNode::Ptr &node_parent)
Definition: xml_parsing.cpp:485
tinyxml2::XMLDocument::Error
bool Error() const
Return true if there was an error parsing the document.
Definition: tinyxml2.h:1881
BT::PortDirection::INOUT
@ INOUT
tinyxml2::XMLNode::InsertFirstChild
XMLNode * InsertFirstChild(XMLNode *addThis)
Definition: tinyxml2.cpp:925
ros::package::getPath
ROSLIB_DECL std::string getPath(const std::string &package_name)
tinyxml2::XMLElement::Attribute
const char * Attribute(const char *name, const char *value=0) const
Definition: tinyxml2.cpp:1595
BT::XMLParser::clearInternalState
void clearInternalState() override
Definition: xml_parsing.cpp:480
BT::XMLParser::loadFromText
void loadFromText(const std::string &xml_text, bool add_includes=true) override
Definition: xml_parsing.cpp:111
minitrace::count
static volatile int count
Definition: minitrace.cpp:55
BT::NodeType::DECORATOR
@ DECORATOR
BT::XMLParser::Pimpl::loadDocImpl
void loadDocImpl(tinyxml2::XMLDocument *doc, bool add_includes)
Definition: xml_parsing.cpp:131
BT::XMLParser::Pimpl::suffix_count
int suffix_count
Definition: xml_parsing.cpp:71
BT::XMLParser::loadFromFile
void loadFromFile(const std::string &filename, bool add_includes=true) override
Definition: xml_parsing.cpp:98
tinyxml2::XMLPrinter
Definition: tinyxml2.h:2237
tinyxml2::XMLElement::SetAttribute
void SetAttribute(const char *name, const char *value)
Sets the named attribute to value.
Definition: tinyxml2.h:1465
BT::XMLParser::registeredBehaviorTrees
std::vector< std::string > registeredBehaviorTrees() const override
Definition: xml_parsing.cpp:121
BT::PortsRemapping
std::unordered_map< std::string, std::string > PortsRemapping
Definition: tree_node.h:42
BT::Tree
Struct used to store a tree. If this object goes out of scope, the tree is destroyed.
Definition: bt_factory.h:125
tinyxml2::XMLDocument::LoadFile
XMLError LoadFile(const char *filename)
Definition: tinyxml2.cpp:2312
BT::NodeType::SUBTREE
@ SUBTREE
tinyxml2::XMLNode::NextSiblingElement
const XMLElement * NextSiblingElement(const char *name=0) const
Get the next (right) sibling element of this node, with an optionally supplied name.
Definition: tinyxml2.cpp:1018
BT::TreeNode::Ptr
std::shared_ptr< TreeNode > Ptr
Definition: tree_node.h:58
BT::DecoratorNode
Definition: decorator_node.h:8
BT::Tree::nodes
std::vector< TreeNode::Ptr > nodes
Definition: bt_factory.h:128
manifest
string manifest
BT::NodeConfiguration::input_ports
PortsRemapping input_ports
Definition: tree_node.h:50
tinyxml2::XMLDocument::NewElement
XMLElement * NewElement(const char *name)
Definition: tinyxml2.cpp:2239
BT::TreeNode::isBlackboardPointer
static bool isBlackboardPointer(StringView str)
Definition: tree_node.cpp:145
BT::NodeConfiguration
Definition: tree_node.h:44
BT::PortDirection::OUTPUT
@ OUTPUT
BT::IsReservedPortname
bool IsReservedPortname(StringView name)
Definition: basic_types.h:219
BT::NodeConfiguration::output_ports
PortsRemapping output_ports
Definition: tree_node.h:51
BT::BehaviorTreeFactory::manifests
const std::unordered_map< std::string, TreeNodeManifest > & manifests() const
Manifests of all the registered TreeNodes.
Definition: bt_factory.cpp:268
tinyxml2::XMLAttribute
Definition: tinyxml2.h:1140
BT::toStr
std::string toStr(T value)
Definition: basic_types.h:141
tinyxml2::XMLPrinter::CStr
const char * CStr() const
Definition: tinyxml2.h:2306
BT::PortDirection
PortDirection
Definition: basic_types.h:48
tinyxml2::XMLElement::FirstAttribute
const XMLAttribute * FirstAttribute() const
Return the first attribute in the list.
Definition: tinyxml2.h:1514
tinyxml2::XMLPrinter::CStrSize
int CStrSize() const
Definition: tinyxml2.h:2314
minitrace::buffer
static raw_event_t * buffer
Definition: minitrace.cpp:54
BT::XMLParser::Pimpl::current_path
filesystem::path current_path
Definition: xml_parsing.cpp:69
BT::StrEqual
auto StrEqual
Definition: xml_parsing.cpp:45
BT::convertFromString< bool >
bool convertFromString< bool >(StringView str)
Definition: basic_types.cpp:178
BT::Tree::initialize
void initialize()
Definition: bt_factory.h:153
BT::XMLParser::instantiateTree
Tree instantiateTree(const Blackboard::Ptr &root_blackboard, std::string main_tree_to_execute={}) override
Definition: xml_parsing.cpp:439
BT::XMLParser::XMLParser
XMLParser(const BehaviorTreeFactory &factory)
Definition: xml_parsing.cpp:90
BT::XMLParser::_p
Pimpl * _p
Definition: xml_parsing.h:37
BT::TreeNode::getRemappedKey
static Optional< StringView > getRemappedKey(StringView port_name, StringView remapping_value)
Definition: tree_node.cpp:179
BT::RuntimeError
Definition: exceptions.h:58
tinyxml2::XMLElement
Definition: tinyxml2.h:1264
BT::buildTreeFromFile
Tree buildTreeFromFile(const BehaviorTreeFactory &factory, const std::string &filename, const Blackboard::Ptr &blackboard)
Definition: xml_parsing.cpp:904
demangle_util.h
tinyxml2::XMLDocument::RootElement
XMLElement * RootElement()
Definition: tinyxml2.h:1810
xml_parsing.h
BT::PortDirection::INPUT
@ INPUT
BT::XMLParser::Pimpl::clear
void clear()
Definition: xml_parsing.cpp:77
BT::BehaviorTreeFactory
The BehaviorTreeFactory is used to create instances of a TreeNode at run-time.
Definition: bt_factory.h:251
package.h
BT::XMLParser::Pimpl::tree_roots
std::map< std::string, const XMLElement * > tree_roots
Definition: xml_parsing.cpp:65
BT::Blackboard::create
static Blackboard::Ptr create(Blackboard::Ptr parent={})
Definition: blackboard.h:36
BT::PortInfo::direction
PortDirection direction() const
Definition: basic_types.cpp:287
BT::NodeConfiguration::blackboard
Blackboard::Ptr blackboard
Definition: tree_node.h:49
tinyxml2::XMLDocument::Print
void Print(XMLPrinter *streamer=0) const
Definition: tinyxml2.cpp:2446
BT::XMLParser::Pimpl
Definition: xml_parsing.cpp:49
tinyxml2::XMLDocument::ErrorName
const char * ErrorName() const
Definition: tinyxml2.cpp:2512
BT::buildTreeFromText
Tree buildTreeFromText(const BehaviorTreeFactory &factory, const std::string &text, const Blackboard::Ptr &blackboard)
Definition: xml_parsing.cpp:896
BT::XMLParser::Pimpl::opened_documents
std::list< std::unique_ptr< tinyxml2::XMLDocument > > opened_documents
Definition: xml_parsing.cpp:64
BT::PortInfo::defaultValue
const std::string & defaultValue() const
Definition: basic_types.cpp:330
BT::XMLParser::Pimpl::recursivelyCreateTree
void recursivelyCreateTree(const std::string &tree_ID, Tree &output_tree, Blackboard::Ptr blackboard, const TreeNode::Ptr &root_parent)
Definition: xml_parsing.cpp:662
BT::VerifyXML
void VerifyXML(const std::string &xml_text, const std::unordered_map< std::string, NodeType > &registered_nodes)
tinyxml2::XMLDocument
Definition: tinyxml2.h:1716
BT::Tree::blackboard_stack
std::vector< Blackboard::Ptr > blackboard_stack
Definition: bt_factory.h:129
tinyxml2
Definition: tinyxml2.cpp:133
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:15
BT::Blackboard::Ptr
std::shared_ptr< Blackboard > Ptr
Definition: blackboard.h:25
path
Simple class for manipulating paths on Linux/Windows/Mac OS.
Definition: path.h:42
tinyxml2.h
blackboard.h
tinyxml2::XMLNode::InsertEndChild
XMLNode * InsertEndChild(XMLNode *addThis)
Definition: tinyxml2.cpp:895
BT::SubtreePlusNode
The SubtreePlus is a new kind of subtree that gives you much more control over remapping:
Definition: subtree_node.h:78
xml_text
static const char * xml_text
Definition: ex01_wrap_legacy.cpp:52
BT::StringView
nonstd::string_view StringView
Definition: basic_types.h:55
BT::ControlNode
Definition: control_node.h:21
BT::XMLParser::~XMLParser
~XMLParser() override
Definition: xml_parsing.cpp:93
BT::writeTreeNodesModelXML
std::string writeTreeNodesModelXML(const BehaviorTreeFactory &factory, bool include_builtin=false)
Definition: xml_parsing.cpp:797
tinyxml2::XMLDocument::Parse
XMLError Parse(const char *xml, size_t nBytes=static_cast< size_t >(-1))
Definition: tinyxml2.cpp:2415
BT::XMLParser::Pimpl::factory
const BehaviorTreeFactory & factory
Definition: xml_parsing.cpp:67
BT::SubtreeNode
The SubtreeNode is a way to wrap an entire Subtree, creating a separated BlackBoard....
Definition: subtree_node.h:14
nonstd::sv_lite::to_string
std::basic_string< CharT, Traits > to_string(basic_string_view< CharT, Traits > v)
Definition: string_view.hpp:1414
BT::TreeNode::stripBlackboardPointer
static StringView stripBlackboardPointer(StringView str)
Definition: tree_node.cpp:162
tinyxml2::XMLNode::FirstChildElement
const XMLElement * FirstChildElement(const char *name=0) const
Definition: tinyxml2.cpp:994
tinyxml2::XMLAttribute::Next
const XMLAttribute * Next() const
The next attribute in the list.
Definition: tinyxml2.h:1154
tinyxml2::XMLElement::Name
const char * Name() const
Get the name of an element (which is the Value() of the node.)
Definition: tinyxml2.h:1269
tinyxml2::XMLElement::SetText
void SetText(const char *inText)
Definition: tinyxml2.cpp:1675


behaviortree_cpp_v3
Author(s): Michele Colledanchise, Davide Faconti
autogenerated on Wed Jun 26 2024 02:51:19