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 <cstdio>
14 #include <cstring>
15 #include <functional>
16 #include <iostream>
17 #include <list>
18 #include <sstream>
19 #include <string>
20 #include <typeindex>
21 
22 #if defined(__linux) || defined(__linux__)
23 #pragma GCC diagnostic push
24 #pragma GCC diagnostic ignored "-Wattributes"
25 #endif
26 
27 #include <map>
29 #include "tinyxml2/tinyxml2.h"
30 #include <filesystem>
31 
32 #ifdef USING_ROS
33 #include <ros/package.h>
34 #endif
35 
36 #ifdef USING_ROS2
37 #include <ament_index_cpp/get_package_share_directory.hpp>
38 #endif
39 
43 
44 namespace
45 {
46 std::string xsdAttributeType(const BT::PortInfo& port_info)
47 {
48  if(port_info.direction() == BT::PortDirection::OUTPUT)
49  {
50  return "blackboardType";
51  }
52  const auto& type_info = port_info.type();
53  if((type_info == typeid(int)) or (type_info == typeid(unsigned int)))
54  {
55  return "integerOrBlackboardType";
56  }
57  else if(type_info == typeid(double))
58  {
59  return "decimalOrBlackboardType";
60  }
61  else if(type_info == typeid(bool))
62  {
63  return "booleanOrBlackboardType";
64  }
65  else if(type_info == typeid(std::string))
66  {
67  return "stringOrBlackboardType";
68  }
69 
70  return std::string();
71 }
72 
73 } // namespace
74 
75 namespace BT
76 {
77 using namespace tinyxml2;
78 
79 auto StrEqual = [](const char* str1, const char* str2) -> bool {
80  return strcmp(str1, str2) == 0;
81 };
82 
84 {
85  std::unordered_map<std::string, BT::PortInfo> ports;
86 };
87 
89 {
90  TreeNode::Ptr createNodeFromXML(const XMLElement* element,
91  const Blackboard::Ptr& blackboard,
92  const TreeNode::Ptr& node_parent,
93  const std::string& prefix_path, Tree& output_tree);
94 
95  void recursivelyCreateSubtree(const std::string& tree_ID, const std::string& tree_path,
96  const std::string& prefix_path, Tree& output_tree,
97  Blackboard::Ptr blackboard,
98  const TreeNode::Ptr& root_node);
99 
100  void getPortsRecursively(const XMLElement* element,
101  std::vector<std::string>& output_ports);
102 
103  void loadDocImpl(XMLDocument* doc, bool add_includes);
104 
105  std::list<std::unique_ptr<XMLDocument> > opened_documents;
106  std::map<std::string, const XMLElement*> tree_roots;
107 
109 
110  std::filesystem::path current_path;
111  std::map<std::string, SubtreeModel> subtree_models;
112 
114 
115  explicit PImpl(const BehaviorTreeFactory& fact)
116  : factory(fact), current_path(std::filesystem::current_path()), suffix_count(0)
117  {}
118 
119  void clear()
120  {
121  suffix_count = 0;
122  current_path = std::filesystem::current_path();
123  opened_documents.clear();
124  tree_roots.clear();
125  }
126 
127 private:
128  void loadSubtreeModel(const XMLElement* xml_root);
129 };
130 
131 #if defined(__linux) || defined(__linux__)
132 #pragma GCC diagnostic pop
133 #endif
134 
135 XMLParser::XMLParser(const BehaviorTreeFactory& factory) : _p(new PImpl(factory))
136 {}
137 
139 {
140  this->_p = std::move(other._p);
141 }
142 
144 {
145  this->_p = std::move(other._p);
146  return *this;
147 }
148 
150 {}
151 
152 void XMLParser::loadFromFile(const std::filesystem::path& filepath, bool add_includes)
153 {
154  _p->opened_documents.emplace_back(new XMLDocument());
155 
156  XMLDocument* doc = _p->opened_documents.back().get();
157  doc->LoadFile(filepath.string().c_str());
158 
159  _p->current_path = std::filesystem::absolute(filepath.parent_path());
160 
161  _p->loadDocImpl(doc, add_includes);
162 }
163 
164 void XMLParser::loadFromText(const std::string& xml_text, bool add_includes)
165 {
166  _p->opened_documents.emplace_back(new XMLDocument());
167 
168  XMLDocument* doc = _p->opened_documents.back().get();
169  doc->Parse(xml_text.c_str(), xml_text.size());
170 
171  _p->loadDocImpl(doc, add_includes);
172 }
173 
174 std::vector<std::string> XMLParser::registeredBehaviorTrees() const
175 {
176  std::vector<std::string> out;
177  for(const auto& it : _p->tree_roots)
178  {
179  out.push_back(it.first);
180  }
181  return out;
182 }
183 
185 {
186  for(auto models_node = xml_root->FirstChildElement("TreeNodesModel");
187  models_node != nullptr; models_node = models_node->NextSiblingElement("TreeNodesMo"
188  "del"))
189  {
190  for(auto sub_node = models_node->FirstChildElement("SubTree"); sub_node != nullptr;
191  sub_node = sub_node->NextSiblingElement("SubTree"))
192  {
193  auto subtree_id = sub_node->Attribute("ID");
194  auto& subtree_model = subtree_models[subtree_id];
195 
196  std::pair<const char*, BT::PortDirection> port_types[3] = {
197  { "input_port", BT::PortDirection::INPUT },
198  { "output_port", BT::PortDirection::OUTPUT },
199  { "inout_port", BT::PortDirection::INOUT }
200  };
201 
202  for(const auto& [name, direction] : port_types)
203  {
204  for(auto port_node = sub_node->FirstChildElement(name); port_node != nullptr;
205  port_node = port_node->NextSiblingElement(name))
206  {
207  BT::PortInfo port(direction);
208  auto name = port_node->Attribute("name");
209  if(!name)
210  {
211  throw RuntimeError("Missing attribute [name] in port (SubTree model)");
212  }
213  if(auto default_value = port_node->Attribute("default"))
214  {
215  port.setDefaultValue(default_value);
216  }
217  if(auto description = port_node->Attribute("description"))
218  {
219  port.setDescription(description);
220  }
221  subtree_model.ports[name] = std::move(port);
222  }
223  }
224  }
225  }
226 }
227 
228 void XMLParser::PImpl::loadDocImpl(XMLDocument* doc, bool add_includes)
229 {
230  if(doc->Error())
231  {
232  char buffer[512];
233  snprintf(buffer, sizeof buffer, "Error parsing the XML: %s", doc->ErrorStr());
234  throw RuntimeError(buffer);
235  }
236 
237  const XMLElement* xml_root = doc->RootElement();
238 
239  auto format = xml_root->Attribute("BTCPP_format");
240  if(!format)
241  {
242  std::cout << "Warnings: The first tag of the XML (<root>) should contain the "
243  "attribute [BTCPP_format=\"4\"]\n"
244  << "Please check if your XML is compatible with version 4.x of BT.CPP"
245  << std::endl;
246  }
247 
248  // recursively include other files
249  for(auto incl_node = xml_root->FirstChildElement("include"); incl_node != nullptr;
250  incl_node = incl_node->NextSiblingElement("include"))
251  {
252  if(!add_includes)
253  {
254  break;
255  }
256 
257  std::filesystem::path file_path(incl_node->Attribute("path"));
258  const char* ros_pkg_relative_path = incl_node->Attribute("ros_pkg");
259 
260  if(ros_pkg_relative_path)
261  {
262  if(file_path.is_absolute())
263  {
264  std::cout << "WARNING: <include path=\"...\"> contains an absolute path.\n"
265  << "Attribute [ros_pkg] will be ignored." << std::endl;
266  }
267  else
268  {
269  std::string ros_pkg_path;
270 #ifdef USING_ROS
271  ros_pkg_path = ros::package::getPath(ros_pkg_relative_path);
272 #elif defined USING_ROS2
273  ros_pkg_path =
274  ament_index_cpp::get_package_share_directory(ros_pkg_relative_path);
275 #else
276  throw RuntimeError("Using attribute [ros_pkg] in <include>, but this library was "
277  "compiled without ROS support. Recompile the BehaviorTree.CPP "
278  "using catkin");
279 #endif
280  file_path = std::filesystem::path(ros_pkg_path) / file_path;
281  }
282  }
283 
284  if(!file_path.is_absolute())
285  {
286  file_path = current_path / file_path;
287  }
288 
289  opened_documents.emplace_back(new XMLDocument());
290  XMLDocument* next_doc = opened_documents.back().get();
291 
292  // change current path to the included file for handling additional relative paths
293  const auto previous_path = current_path;
294  current_path = std::filesystem::absolute(file_path.parent_path());
295 
296  next_doc->LoadFile(file_path.string().c_str());
297  loadDocImpl(next_doc, add_includes);
298 
299  // reset current path to the previous value
300  current_path = previous_path;
301  }
302 
303  // Collect the names of all nodes registered with the behavior tree factory
304  std::unordered_map<std::string, BT::NodeType> registered_nodes;
305  for(const auto& it : factory.manifests())
306  {
307  registered_nodes.insert({ it.first, it.second.type });
308  }
309 
310  XMLPrinter printer;
311  doc->Print(&printer);
312  auto xml_text = std::string(printer.CStr(), size_t(printer.CStrSize()));
313 
314  // Verify the validity of the XML before adding any behavior trees to the parser's list of registered trees
315  VerifyXML(xml_text, registered_nodes);
316 
317  loadSubtreeModel(xml_root);
318 
319  // Register each BehaviorTree within the XML
320  for(auto bt_node = xml_root->FirstChildElement("BehaviorTree"); bt_node != nullptr;
321  bt_node = bt_node->NextSiblingElement("BehaviorTree"))
322  {
323  std::string tree_name;
324  if(bt_node->Attribute("ID"))
325  {
326  tree_name = bt_node->Attribute("ID");
327  }
328  else
329  {
330  tree_name = "BehaviorTree_" + std::to_string(suffix_count++);
331  }
332 
333  tree_roots[tree_name] = bt_node;
334  }
335 }
336 
337 void VerifyXML(const std::string& xml_text,
338  const std::unordered_map<std::string, BT::NodeType>& registered_nodes)
339 {
340  XMLDocument doc;
341  auto xml_error = doc.Parse(xml_text.c_str(), xml_text.size());
342  if(xml_error)
343  {
344  char buffer[512];
345  snprintf(buffer, sizeof buffer, "Error parsing the XML: %s", doc.ErrorName());
346  throw RuntimeError(buffer);
347  }
348 
349  //-------- Helper functions (lambdas) -----------------
350  auto ThrowError = [&](int line_num, const std::string& text) {
351  char buffer[512];
352  snprintf(buffer, sizeof buffer, "Error at line %d: -> %s", line_num, text.c_str());
353  throw RuntimeError(buffer);
354  };
355 
356  auto ChildrenCount = [](const XMLElement* parent_node) {
357  int count = 0;
358  for(auto node = parent_node->FirstChildElement(); node != nullptr;
359  node = node->NextSiblingElement())
360  {
361  count++;
362  }
363  return count;
364  };
365  //-----------------------------
366 
367  const XMLElement* xml_root = doc.RootElement();
368 
369  if(!xml_root || !StrEqual(xml_root->Name(), "root"))
370  {
371  throw RuntimeError("The XML must have a root node called <root>");
372  }
373  //-------------------------------------------------
374  auto models_root = xml_root->FirstChildElement("TreeNodesModel");
375  auto meta_sibling =
376  models_root ? models_root->NextSiblingElement("TreeNodesModel") : nullptr;
377 
378  if(meta_sibling)
379  {
380  ThrowError(meta_sibling->GetLineNum(), " Only a single node <TreeNodesModel> is "
381  "supported");
382  }
383  if(models_root)
384  {
385  // not having a MetaModel is not an error. But consider that the
386  // Graphical editor needs it.
387  for(auto node = xml_root->FirstChildElement(); node != nullptr;
388  node = node->NextSiblingElement())
389  {
390  const std::string name = node->Name();
391  if(name == "Action" || name == "Decorator" || name == "SubTree" ||
392  name == "Condition" || name == "Control")
393  {
394  const char* ID = node->Attribute("ID");
395  if(!ID)
396  {
397  ThrowError(node->GetLineNum(), "Error at line %d: -> The attribute "
398  "[ID] is mandatory");
399  }
400  }
401  }
402  }
403  //-------------------------------------------------
404 
405  int behavior_tree_count = 0;
406  for(auto child = xml_root->FirstChildElement(); child != nullptr;
407  child = child->NextSiblingElement())
408  {
409  behavior_tree_count++;
410  }
411 
412  // function to be called recursively
413  std::function<void(const XMLElement*)> recursiveStep;
414 
415  recursiveStep = [&](const XMLElement* node) {
416  const int children_count = ChildrenCount(node);
417  const std::string name = node->Name();
418  const std::string ID = node->Attribute("ID") ? node->Attribute("ID") : "";
419  const int line_number = node->GetLineNum();
420 
421  if(name == "Decorator")
422  {
423  if(children_count != 1)
424  {
425  ThrowError(line_number, "The tag <Decorator> must have exactly 1 "
426  "child");
427  }
428  if(ID.empty())
429  {
430  ThrowError(line_number, "The tag <Decorator> must have the "
431  "attribute [ID]");
432  }
433  }
434  else if(name == "Action")
435  {
436  if(children_count != 0)
437  {
438  ThrowError(line_number, "The tag <Action> must not have any "
439  "child");
440  }
441  if(ID.empty())
442  {
443  ThrowError(line_number, "The tag <Action> must have the "
444  "attribute [ID]");
445  }
446  }
447  else if(name == "Condition")
448  {
449  if(children_count != 0)
450  {
451  ThrowError(line_number, "The tag <Condition> must not have any "
452  "child");
453  }
454  if(ID.empty())
455  {
456  ThrowError(line_number, "The tag <Condition> must have the "
457  "attribute [ID]");
458  }
459  }
460  else if(name == "Control")
461  {
462  if(children_count == 0)
463  {
464  ThrowError(line_number, "The tag <Control> must have at least 1 "
465  "child");
466  }
467  if(ID.empty())
468  {
469  ThrowError(line_number, "The tag <Control> must have the "
470  "attribute [ID]");
471  }
472  }
473  else if(name == "SubTree")
474  {
475  if(children_count != 0)
476  {
477  ThrowError(line_number, "<SubTree> should not have any child");
478  }
479  if(ID.empty())
480  {
481  ThrowError(line_number, "The tag <SubTree> must have the "
482  "attribute [ID]");
483  }
484  if(registered_nodes.count(ID) != 0)
485  {
486  ThrowError(line_number, "The attribute [ID] of tag <SubTree> must "
487  "not use the name of a registered Node");
488  }
489  }
490  else if(name == "BehaviorTree")
491  {
492  if(ID.empty() && behavior_tree_count > 1)
493  {
494  ThrowError(line_number, "The tag <BehaviorTree> must have the "
495  "attribute [ID]");
496  }
497  if(children_count != 1)
498  {
499  ThrowError(line_number, "The tag <BehaviorTree> must have exactly 1 "
500  "child");
501  }
502  if(registered_nodes.count(ID) != 0)
503  {
504  ThrowError(line_number, "The attribute [ID] of tag <BehaviorTree> "
505  "must not use the name of a registered Node");
506  }
507  }
508  else
509  {
510  // search in the factory and the list of subtrees
511  const auto search = registered_nodes.find(name);
512  bool found = (search != registered_nodes.end());
513  if(!found)
514  {
515  ThrowError(line_number, std::string("Node not recognized: ") + name);
516  }
517 
518  if(search->second == NodeType::DECORATOR)
519  {
520  if(children_count != 1)
521  {
522  ThrowError(line_number,
523  std::string("The node <") + name + "> must have exactly 1 child");
524  }
525  }
526  else if(search->second == NodeType::CONTROL)
527  {
528  if(children_count == 0)
529  {
530  ThrowError(line_number,
531  std::string("The node <") + name + "> must have 1 or more children");
532  }
533  }
534  }
535  //recursion
536  for(auto child = node->FirstChildElement(); child != nullptr;
537  child = child->NextSiblingElement())
538  {
539  recursiveStep(child);
540  }
541  };
542 
543  for(auto bt_root = xml_root->FirstChildElement("BehaviorTree"); bt_root != nullptr;
544  bt_root = bt_root->NextSiblingElement("BehaviorTree"))
545  {
546  recursiveStep(bt_root);
547  }
548 }
549 
551  std::string main_tree_ID)
552 {
553  Tree output_tree;
554 
555  // use the main_tree_to_execute argument if it was provided by the user
556  // or the one in the FIRST document opened
557  if(main_tree_ID.empty())
558  {
559  XMLElement* first_xml_root = _p->opened_documents.front()->RootElement();
560 
561  if(auto main_tree_attribute = first_xml_root->Attribute("main_tree_to_execute"))
562  {
563  main_tree_ID = main_tree_attribute;
564  }
565  else if(_p->tree_roots.size() == 1)
566  {
567  // special case: there is only one registered BT.
568  main_tree_ID = _p->tree_roots.begin()->first;
569  }
570  else
571  {
572  throw RuntimeError("[main_tree_to_execute] was not specified correctly");
573  }
574  }
575 
576  //--------------------------------------
577  if(!root_blackboard)
578  {
579  throw RuntimeError("XMLParser::instantiateTree needs a non-empty "
580  "root_blackboard");
581  }
582 
583  _p->recursivelyCreateSubtree(main_tree_ID, {}, {}, output_tree, root_blackboard,
584  TreeNode::Ptr());
585  output_tree.initialize();
586  return output_tree;
587 }
588 
590 {
591  _p->clear();
592 }
593 
595  const Blackboard::Ptr& blackboard,
596  const TreeNode::Ptr& node_parent,
597  const std::string& prefix_path,
598  Tree& output_tree)
599 {
600  const auto element_name = element->Name();
601  const auto element_ID = element->Attribute("ID");
602 
603  auto node_type = convertFromString<NodeType>(element_name);
604  // name used by the factory
605  std::string type_ID;
606 
607  if(node_type == NodeType::UNDEFINED)
608  {
609  // This is the case of nodes like <MyCustomAction>
610  // check if the factory has this name
611  if(factory.builders().count(element_name) == 0)
612  {
613  throw RuntimeError(element_name, " is not a registered node");
614  }
615  type_ID = element_name;
616 
617  if(element_ID)
618  {
619  throw RuntimeError("Attribute [ID] is not allowed in <", type_ID, ">");
620  }
621  }
622  else
623  {
624  // in this case, it is mandatory to have a field "ID"
625  if(!element_ID)
626  {
627  throw RuntimeError("Attribute [ID] is mandatory in <", type_ID, ">");
628  }
629  type_ID = element_ID;
630  }
631 
632  // By default, the instance name is equal to ID, unless the
633  // attribute [name] is present.
634  const char* attr_name = element->Attribute("name");
635  const std::string instance_name = (attr_name != nullptr) ? attr_name : type_ID;
636 
637  const TreeNodeManifest* manifest = nullptr;
638 
639  auto manifest_it = factory.manifests().find(type_ID);
640  if(manifest_it != factory.manifests().end())
641  {
642  manifest = &manifest_it->second;
643  }
644 
645  PortsRemapping port_remap;
646  for(const XMLAttribute* att = element->FirstAttribute(); att; att = att->Next())
647  {
648  if(IsAllowedPortName(att->Name()))
649  {
650  const std::string port_name = att->Name();
651  const std::string port_value = att->Value();
652 
653  if(manifest)
654  {
655  auto port_model_it = manifest->ports.find(port_name);
656  if(port_model_it == manifest->ports.end())
657  {
658  throw RuntimeError(StrCat("a port with name [", port_name,
659  "] is found in the XML, but not in the "
660  "providedPorts()"));
661  }
662  else
663  {
664  const auto& port_model = port_model_it->second;
665  bool is_blacbkboard = port_value.size() >= 3 && port_value.front() == '{' &&
666  port_value.back() == '}';
667  // let's test already if conversion is possible
668  if(!is_blacbkboard && port_model.converter() && port_model.isStronglyTyped())
669  {
670  // This may throw
671  try
672  {
673  port_model.converter()(port_value);
674  }
675  catch(std::exception& ex)
676  {
677  auto msg = StrCat("The port with name \"", port_name, "\" and value \"",
678  port_value, "\" can not be converted to ",
679  port_model.typeName());
680  throw LogicError(msg);
681  }
682  }
683  }
684  }
685 
686  port_remap[port_name] = port_value;
687  }
688  }
689 
690  NodeConfig config;
691  config.blackboard = blackboard;
692  config.path = prefix_path + instance_name;
693  config.uid = output_tree.getUID();
694  config.manifest = manifest;
695 
696  if(type_ID == instance_name)
697  {
698  config.path += std::string("::") + std::to_string(config.uid);
699  }
700 
701  auto AddCondition = [&](auto& conditions, const char* attr_name, auto ID) {
702  if(auto script = element->Attribute(attr_name))
703  {
704  conditions.insert({ ID, std::string(script) });
705  }
706  };
707 
708  for(int i = 0; i < int(PreCond::COUNT_); i++)
709  {
710  auto pre = static_cast<PreCond>(i);
711  AddCondition(config.pre_conditions, toStr(pre).c_str(), pre);
712  }
713  for(int i = 0; i < int(PostCond::COUNT_); i++)
714  {
715  auto post = static_cast<PostCond>(i);
716  AddCondition(config.post_conditions, toStr(post).c_str(), post);
717  }
718 
719  //---------------------------------------------
720  TreeNode::Ptr new_node;
721 
722  if(node_type == NodeType::SUBTREE)
723  {
724  config.input_ports = port_remap;
725  new_node =
726  factory.instantiateTreeNode(instance_name, toStr(NodeType::SUBTREE), config);
727  auto subtree_node = dynamic_cast<SubTreeNode*>(new_node.get());
728  subtree_node->setSubtreeID(type_ID);
729  }
730  else
731  {
732  if(!manifest)
733  {
734  auto msg = StrCat("Missing manifest for element_ID: ", element_ID,
735  ". It shouldn't happen. Please report this issue.");
736  throw RuntimeError(msg);
737  }
738 
739  //Check that name in remapping can be found in the manifest
740  for(const auto& [name_in_subtree, _] : port_remap)
741  {
742  if(manifest->ports.count(name_in_subtree) == 0)
743  {
744  throw RuntimeError("Possible typo? In the XML, you tried to remap port \"",
745  name_in_subtree, "\" in node [", config.path, "(type ",
746  type_ID,
747  ")], but the manifest/model of this node does not contain a "
748  "port "
749  "with this name.");
750  }
751  }
752 
753  // Initialize the ports in the BB to set the type
754  for(const auto& [port_name, port_info] : manifest->ports)
755  {
756  auto remap_it = port_remap.find(port_name);
757  if(remap_it == port_remap.end())
758  {
759  continue;
760  }
761  StringView remapped_port = remap_it->second;
762 
763  if(auto param_res = TreeNode::getRemappedKey(port_name, remapped_port))
764  {
765  // port_key will contain the key to find the entry in the blackboard
766  const auto port_key = static_cast<std::string>(param_res.value());
767 
768  // if the entry already exists, check that the type is the same
769  if(auto prev_info = blackboard->entryInfo(port_key))
770  {
771  // Check consistency of types.
772  bool const port_type_mismatch =
773  (prev_info->isStronglyTyped() && port_info.isStronglyTyped() &&
774  prev_info->type() != port_info.type());
775 
776  // special case related to convertFromString
777  bool const string_input = (prev_info->type() == typeid(std::string));
778 
779  if(port_type_mismatch && !string_input)
780  {
781  blackboard->debugMessage();
782 
783  throw RuntimeError("The creation of the tree failed because the port [",
784  port_key, "] was initially created with type [",
785  demangle(prev_info->type()), "] and, later type [",
786  demangle(port_info.type()), "] was used somewhere else.");
787  }
788  }
789  else
790  {
791  // not found, insert for the first time.
792  blackboard->createEntry(port_key, port_info);
793  }
794  }
795  }
796 
797  // Set the port direction in config
798  for(const auto& remap_it : port_remap)
799  {
800  const auto& port_name = remap_it.first;
801  auto port_it = manifest->ports.find(port_name);
802  if(port_it != manifest->ports.end())
803  {
804  auto direction = port_it->second.direction();
805  if(direction != PortDirection::OUTPUT)
806  {
807  config.input_ports.insert(remap_it);
808  }
809  if(direction != PortDirection::INPUT)
810  {
811  config.output_ports.insert(remap_it);
812  }
813  }
814  }
815 
816  // use default value if available for empty ports. Only inputs
817  for(const auto& port_it : manifest->ports)
818  {
819  const std::string& port_name = port_it.first;
820  const PortInfo& port_info = port_it.second;
821 
822  const auto direction = port_info.direction();
823  const auto& default_string = port_info.defaultValueString();
824  if(!default_string.empty())
825  {
826  if(direction != PortDirection::OUTPUT && config.input_ports.count(port_name) == 0)
827  {
828  config.input_ports.insert({ port_name, default_string });
829  }
830 
831  if(direction != PortDirection::INPUT &&
832  config.output_ports.count(port_name) == 0 &&
833  TreeNode::isBlackboardPointer(default_string))
834  {
835  config.output_ports.insert({ port_name, default_string });
836  }
837  }
838  }
839 
840  new_node = factory.instantiateTreeNode(instance_name, type_ID, config);
841  }
842 
843  // add the pointer of this node to the parent
844  if(node_parent != nullptr)
845  {
846  if(auto control_parent = dynamic_cast<ControlNode*>(node_parent.get()))
847  {
848  control_parent->addChild(new_node.get());
849  }
850  else if(auto decorator_parent = dynamic_cast<DecoratorNode*>(node_parent.get()))
851  {
852  decorator_parent->setChild(new_node.get());
853  }
854  }
855 
856  return new_node;
857 }
858 
859 void BT::XMLParser::PImpl::recursivelyCreateSubtree(const std::string& tree_ID,
860  const std::string& tree_path,
861  const std::string& prefix_path,
862  Tree& output_tree,
863  Blackboard::Ptr blackboard,
864  const TreeNode::Ptr& root_node)
865 {
866  std::function<void(const TreeNode::Ptr&, Tree::Subtree::Ptr, std::string,
867  const XMLElement*)>
868  recursiveStep;
869 
870  recursiveStep = [&](TreeNode::Ptr parent_node, Tree::Subtree::Ptr subtree,
871  std::string prefix, const XMLElement* element) {
872  // create the node
873  auto node = createNodeFromXML(element, blackboard, parent_node, prefix, output_tree);
874  subtree->nodes.push_back(node);
875 
876  // common case: iterate through all children
877  if(node->type() != NodeType::SUBTREE)
878  {
879  for(auto child_element = element->FirstChildElement(); child_element;
880  child_element = child_element->NextSiblingElement())
881  {
882  recursiveStep(node, subtree, prefix, child_element);
883  }
884  }
885  else // special case: SubTreeNode
886  {
887  auto new_bb = Blackboard::create(blackboard);
888  const std::string subtree_ID = element->Attribute("ID");
889  std::unordered_map<std::string, std::string> subtree_remapping;
890  bool do_autoremap = false;
891 
892  for(auto attr = element->FirstAttribute(); attr != nullptr; attr = attr->Next())
893  {
894  std::string attr_name = attr->Name();
895  std::string attr_value = attr->Value();
896  if(attr_value == "{=}")
897  {
898  attr_value = StrCat("{", attr_name, "}");
899  }
900 
901  if(attr_name == "_autoremap")
902  {
903  do_autoremap = convertFromString<bool>(attr_value);
904  new_bb->enableAutoRemapping(do_autoremap);
905  continue;
906  }
907  if(!IsAllowedPortName(attr->Name()))
908  {
909  continue;
910  }
911  subtree_remapping.insert({ attr_name, attr_value });
912  }
913  // check if this subtree has a model. If it does,
914  // we want to check if all the mandatory ports were remapped and
915  // add default ones, if necessary
916  auto subtree_model_it = subtree_models.find(subtree_ID);
917  if(subtree_model_it != subtree_models.end())
918  {
919  const auto& subtree_model_ports = subtree_model_it->second.ports;
920  // check if:
921  // - remapping contains mondatory ports
922  // - if any of these has default value
923  for(const auto& [port_name, port_info] : subtree_model_ports)
924  {
925  auto it = subtree_remapping.find(port_name);
926  // don't override existing remapping
927  if(it == subtree_remapping.end() && !do_autoremap)
928  {
929  // remapping is not explicitly defined in the XML: use the model
930  if(port_info.defaultValueString().empty())
931  {
932  auto msg = StrCat("In the <TreeNodesModel> the <Subtree ID=\"", subtree_ID,
933  "\"> is defining a mandatory port called [", port_name,
934  "], but you are not remapping it");
935  throw RuntimeError(msg);
936  }
937  else
938  {
939  subtree_remapping.insert({ port_name, port_info.defaultValueString() });
940  }
941  }
942  }
943  }
944 
945  for(const auto& [attr_name, attr_value] : subtree_remapping)
946  {
947  if(TreeNode::isBlackboardPointer(attr_value))
948  {
949  // do remapping
950  StringView port_name = TreeNode::stripBlackboardPointer(attr_value);
951  new_bb->addSubtreeRemapping(attr_name, port_name);
952  }
953  else
954  {
955  // constant string: just set that constant value into the BB
956  // IMPORTANT: this must not be autoremapped!!!
957  new_bb->enableAutoRemapping(false);
958  new_bb->set(attr_name, static_cast<std::string>(attr_value));
959  new_bb->enableAutoRemapping(do_autoremap);
960  }
961  }
962 
963  std::string subtree_path = subtree->instance_name;
964  if(!subtree_path.empty())
965  {
966  subtree_path += "/";
967  }
968  if(auto name = element->Attribute("name"))
969  {
970  subtree_path += name;
971  }
972  else
973  {
974  subtree_path += subtree_ID + "::" + std::to_string(node->UID());
975  }
976 
977  recursivelyCreateSubtree(subtree_ID,
978  subtree_path, // name
979  subtree_path + "/", //prefix
980  output_tree, new_bb, node);
981  }
982  };
983 
984  auto it = tree_roots.find(tree_ID);
985  if(it == tree_roots.end())
986  {
987  throw std::runtime_error(std::string("Can't find a tree with name: ") + tree_ID);
988  }
989 
990  auto root_element = it->second->FirstChildElement();
991 
992  //-------- start recursion -----------
993 
994  // Append a new subtree to the list
995  auto new_tree = std::make_shared<Tree::Subtree>();
996  new_tree->blackboard = blackboard;
997  new_tree->instance_name = tree_path;
998  new_tree->tree_ID = tree_ID;
999  output_tree.subtrees.push_back(new_tree);
1000 
1001  recursiveStep(root_node, new_tree, prefix_path, root_element);
1002 }
1003 
1005  std::vector<std::string>& output_ports)
1006 {
1007  for(const XMLAttribute* attr = element->FirstAttribute(); attr != nullptr;
1008  attr = attr->Next())
1009  {
1010  const char* attr_name = attr->Name();
1011  const char* attr_value = attr->Value();
1012  if(IsAllowedPortName(attr_name) && TreeNode::isBlackboardPointer(attr_value))
1013  {
1014  auto port_name = TreeNode::stripBlackboardPointer(attr_value);
1015  output_ports.push_back(static_cast<std::string>(port_name));
1016  }
1017  }
1018 
1019  for(auto child_element = element->FirstChildElement(); child_element;
1020  child_element = child_element->NextSiblingElement())
1021  {
1022  getPortsRecursively(child_element, output_ports);
1023  }
1024 }
1025 
1027  XMLElement* model_root)
1028 {
1029  XMLElement* element = doc.NewElement(toStr(model.type).c_str());
1030  element->SetAttribute("ID", model.registration_ID.c_str());
1031 
1032  for(const auto& [port_name, port_info] : model.ports)
1033  {
1034  XMLElement* port_element = nullptr;
1035  switch(port_info.direction())
1036  {
1037  case PortDirection::INPUT:
1038  port_element = doc.NewElement("input_port");
1039  break;
1040  case PortDirection::OUTPUT:
1041  port_element = doc.NewElement("output_port");
1042  break;
1043  case PortDirection::INOUT:
1044  port_element = doc.NewElement("inout_port");
1045  break;
1046  }
1047 
1048  port_element->SetAttribute("name", port_name.c_str());
1049  if(port_info.type() != typeid(void))
1050  {
1051  port_element->SetAttribute("type", BT::demangle(port_info.type()).c_str());
1052  }
1053  if(!port_info.defaultValue().empty())
1054  {
1055  port_element->SetAttribute("default", port_info.defaultValueString().c_str());
1056  }
1057 
1058  if(!port_info.description().empty())
1059  {
1060  port_element->SetText(port_info.description().c_str());
1061  }
1062  element->InsertEndChild(port_element);
1063  }
1064 
1065  if(!model.metadata.empty())
1066  {
1067  auto metadata_root = doc.NewElement("MetadataFields");
1068 
1069  for(const auto& [name, value] : model.metadata)
1070  {
1071  auto metadata_element = doc.NewElement("Metadata");
1072  metadata_element->SetAttribute(name.c_str(), value.c_str());
1073  metadata_root->InsertEndChild(metadata_element);
1074  }
1075 
1076  element->InsertEndChild(metadata_root);
1077  }
1078 
1079  model_root->InsertEndChild(element);
1080 }
1081 
1082 void addTreeToXML(const Tree& tree, XMLDocument& doc, XMLElement* rootXML,
1083  bool add_metadata, bool add_builtin_models)
1084 {
1085  std::function<void(const TreeNode&, XMLElement*)> addNode;
1086  addNode = [&](const TreeNode& node, XMLElement* parent_elem) {
1087  XMLElement* elem = nullptr;
1088 
1089  if(auto subtree = dynamic_cast<const SubTreeNode*>(&node))
1090  {
1091  elem = doc.NewElement(node.registrationName().c_str());
1092  elem->SetAttribute("ID", subtree->subtreeID().c_str());
1093  if(add_metadata)
1094  {
1095  elem->SetAttribute("_fullpath", subtree->config().path.c_str());
1096  }
1097  }
1098  else
1099  {
1100  elem = doc.NewElement(node.registrationName().c_str());
1101  elem->SetAttribute("name", node.name().c_str());
1102  }
1103 
1104  if(add_metadata)
1105  {
1106  elem->SetAttribute("_uid", node.UID());
1107  }
1108 
1109  for(const auto& [name, value] : node.config().input_ports)
1110  {
1111  elem->SetAttribute(name.c_str(), value.c_str());
1112  }
1113  for(const auto& [name, value] : node.config().output_ports)
1114  {
1115  // avoid duplicates, in the case of INOUT ports
1116  if(node.config().input_ports.count(name) == 0)
1117  {
1118  elem->SetAttribute(name.c_str(), value.c_str());
1119  }
1120  }
1121 
1122  for(const auto& [pre, script] : node.config().pre_conditions)
1123  {
1124  elem->SetAttribute(toStr(pre).c_str(), script.c_str());
1125  }
1126  for(const auto& [post, script] : node.config().post_conditions)
1127  {
1128  elem->SetAttribute(toStr(post).c_str(), script.c_str());
1129  }
1130 
1131  parent_elem->InsertEndChild(elem);
1132 
1133  if(auto control = dynamic_cast<const ControlNode*>(&node))
1134  {
1135  for(const auto& child : control->children())
1136  {
1137  addNode(*child, elem);
1138  }
1139  }
1140  else if(auto decorator = dynamic_cast<const DecoratorNode*>(&node))
1141  {
1142  if(decorator->type() != NodeType::SUBTREE)
1143  {
1144  addNode(*decorator->child(), elem);
1145  }
1146  }
1147  };
1148 
1149  for(const auto& subtree : tree.subtrees)
1150  {
1151  XMLElement* subtree_elem = doc.NewElement("BehaviorTree");
1152  subtree_elem->SetAttribute("ID", subtree->tree_ID.c_str());
1153  subtree_elem->SetAttribute("_fullpath", subtree->instance_name.c_str());
1154  rootXML->InsertEndChild(subtree_elem);
1155  addNode(*subtree->nodes.front(), subtree_elem);
1156  }
1157 
1158  XMLElement* model_root = doc.NewElement("TreeNodesModel");
1159  rootXML->InsertEndChild(model_root);
1160 
1161  static const BehaviorTreeFactory temp_factory;
1162 
1163  std::map<std::string, const TreeNodeManifest*> ordered_models;
1164  for(const auto& [registration_ID, model] : tree.manifests)
1165  {
1166  if(add_builtin_models || !temp_factory.builtinNodes().count(registration_ID))
1167  {
1168  ordered_models.insert({ registration_ID, &model });
1169  }
1170  }
1171 
1172  for(const auto& [registration_ID, model] : ordered_models)
1173  {
1174  addNodeModelToXML(*model, doc, model_root);
1175  }
1176 }
1177 
1178 std::string writeTreeNodesModelXML(const BehaviorTreeFactory& factory,
1179  bool include_builtin)
1180 {
1181  XMLDocument doc;
1182 
1183  XMLElement* rootXML = doc.NewElement("root");
1184  rootXML->SetAttribute("BTCPP_format", "4");
1185  doc.InsertFirstChild(rootXML);
1186 
1187  XMLElement* model_root = doc.NewElement("TreeNodesModel");
1188  rootXML->InsertEndChild(model_root);
1189 
1190  std::map<std::string, const TreeNodeManifest*> ordered_models;
1191 
1192  for(const auto& [registration_ID, model] : factory.manifests())
1193  {
1194  if(include_builtin || factory.builtinNodes().count(registration_ID) == 0)
1195  {
1196  ordered_models.insert({ registration_ID, &model });
1197  }
1198  }
1199 
1200  for(const auto& [registration_ID, model] : ordered_models)
1201  {
1202  addNodeModelToXML(*model, doc, model_root);
1203  }
1204 
1205  XMLPrinter printer;
1206  doc.Print(&printer);
1207  return std::string(printer.CStr(), size_t(printer.CStrSize() - 1));
1208 }
1209 
1210 std::string writeTreeXSD(const BehaviorTreeFactory& factory)
1211 {
1212  // There are 2 forms of representation for a node:
1213  // compact: <Sequence .../> and explicit: <Control ID="Sequence" ... />
1214  // Only the compact form is supported because the explicit form doesn't
1215  // make sense with XSD since we would need to allow any attribute.
1216  // Prepare the data
1217 
1218  std::map<std::string, const TreeNodeManifest*> ordered_models;
1219  for(const auto& [registration_id, model] : factory.manifests())
1220  {
1221  ordered_models.insert({ registration_id, &model });
1222  }
1223 
1224  XMLDocument doc;
1225 
1226  // Add the XML declaration
1227  XMLDeclaration* declaration = doc.NewDeclaration("xml version=\"1.0\" "
1228  "encoding=\"UTF-8\"");
1229  doc.InsertFirstChild(declaration);
1230 
1231  // Create the root element with namespace and attributes
1232  // To validate a BT XML file with `schema.xsd` in the same directory:
1233  // <root BTCPP_format="4" main_tree_to_execute="MainTree"
1234  // xmlns:xsi="http://www.w3.org/2001/XMLSchema-instance"
1235  // xsi:noNamespaceSchemaLocation="schema.xsd">
1236  XMLElement* schema_element = doc.NewElement("xs:schema");
1237  schema_element->SetAttribute("xmlns:xs", "http://www.w3.org/2001/XMLSchema");
1238  schema_element->SetAttribute("elementFormDefault", "qualified");
1239  doc.InsertEndChild(schema_element);
1240 
1241  auto parse_and_insert = [&doc](XMLElement* parent_elem, const char* str) {
1242  XMLDocument tmp_doc;
1243  tmp_doc.Parse(str);
1244  if(tmp_doc.Error())
1245  {
1246  std::cerr << "Internal error parsing existing XML: " << tmp_doc.ErrorStr()
1247  << std::endl;
1248  return;
1249  }
1250  for(auto child = tmp_doc.FirstChildElement(); child != nullptr;
1251  child = child->NextSiblingElement())
1252  {
1253  parent_elem->InsertEndChild(child->DeepClone(&doc));
1254  }
1255  };
1256 
1257  // Common elements.
1258  XMLComment* comment = doc.NewComment("Define the common elements");
1259  schema_element->InsertEndChild(comment);
1260 
1261  // TODO: add <xs:whiteSpace value="preserve"/> for `inputPortType` and `outputPortType`.
1262  parse_and_insert(schema_element, R"(
1263  <xs:simpleType name="blackboardType">
1264  <xs:restriction base="xs:string">
1265  <xs:pattern value="\{.*\}"/>
1266  </xs:restriction>
1267  </xs:simpleType>
1268  <xs:simpleType name="booleanOrBlackboardType">
1269  <xs:union memberTypes="xs:boolean blackboardType"/>
1270  </xs:simpleType>
1271  <xs:simpleType name="integerOrBlackboardType">
1272  <xs:union memberTypes="xs:integer blackboardType"/>
1273  </xs:simpleType>
1274  <xs:simpleType name="decimalOrBlackboardType">
1275  <xs:union memberTypes="xs:decimal blackboardType"/>
1276  </xs:simpleType>
1277  <xs:simpleType name="stringOrBlackboardType">
1278  <xs:union memberTypes="xs:string blackboardType"/>
1279  </xs:simpleType>
1280  <xs:simpleType name="descriptionType">
1281  <xs:restriction base="xs:string">
1282  <xs:whiteSpace value="preserve"/>
1283  </xs:restriction>
1284  </xs:simpleType>
1285  <xs:complexType name="inputPortType">
1286  <xs:simpleContent>
1287  <xs:extension base="xs:string">
1288  <xs:attribute name="name" type="xs:string" use="required"/>
1289  <xs:attribute name="type" type="xs:string" use="optional"/>
1290  <xs:attribute name="default" type="xs:string" use="optional"/>
1291  </xs:extension>
1292  </xs:simpleContent>
1293  </xs:complexType>
1294  <xs:complexType name="outputPortType">
1295  <xs:simpleContent>
1296  <xs:extension base="xs:string">
1297  <xs:attribute name="name" type="xs:string" use="required"/>
1298  <xs:attribute name="type" type="xs:string" use="optional"/>
1299  </xs:extension>
1300  </xs:simpleContent>
1301  </xs:complexType>
1302  <xs:attributeGroup name="preconditionAttributeGroup">
1303  <xs:attribute name="_failureIf" type="xs:string" use="optional"/>
1304  <xs:attribute name="_skipIf" type="xs:string" use="optional"/>
1305  <xs:attribute name="_successIf" type="xs:string" use="optional"/>
1306  <xs:attribute name="_while" type="xs:string" use="optional"/>
1307  </xs:attributeGroup>
1308  <xs:attributeGroup name="postconditionAttributeGroup">
1309  <xs:attribute name="_onSuccess" type="xs:string" use="optional"/>
1310  <xs:attribute name="_onFailure" type="xs:string" use="optional"/>
1311  <xs:attribute name="_post" type="xs:string" use="optional"/>
1312  <xs:attribute name="_onHalted" type="xs:string" use="optional"/>
1313  </xs:attributeGroup>)");
1314 
1315  // Common attributes
1316  // Note that we do not add the `ID` attribute because we do not
1317  // support the explicit notation (e.g. <Action ID="Saysomething">).
1318  // Cf. https://www.behaviortree.dev/docs/learn-the-basics/xml_format/#compact-vs-explicit-representation
1319  // There is no way to check attribute validity with the explicit notation with XSD.
1320  // The `ID` attribute for `<SubTree>` is handled separately.
1321  parse_and_insert(schema_element, R"(
1322  <xs:attributeGroup name="commonAttributeGroup">
1323  <xs:attribute name="name" type="xs:string" use="optional"/>
1324  <xs:attributeGroup ref="preconditionAttributeGroup"/>
1325  <xs:attributeGroup ref="postconditionAttributeGroup"/>
1326  </xs:attributeGroup>)");
1327 
1328  // Basic node types
1329  parse_and_insert(schema_element, R"(
1330  <xs:complexType name="treeNodesModelNodeType">
1331  <xs:sequence>
1332  <xs:choice minOccurs="0" maxOccurs="unbounded">
1333  <xs:element name="input_port" type="inputPortType"/>
1334  <xs:element name="output_port" type="outputPortType"/>
1335  </xs:choice>
1336  <xs:element name="description" type="descriptionType" minOccurs="0" maxOccurs="1"/>
1337  </xs:sequence>
1338  <xs:attribute name="ID" type="xs:string" use="required"/>
1339  </xs:complexType>
1340  <xs:group name="treeNodesModelNodeGroup">
1341  <xs:choice>
1342  <xs:element name="Action" type="treeNodesModelNodeType"/>
1343  <xs:element name="Condition" type="treeNodesModelNodeType"/>
1344  <xs:element name="Control" type="treeNodesModelNodeType"/>
1345  <xs:element name="Decorator" type="treeNodesModelNodeType"/>
1346  </xs:choice>
1347  </xs:group>
1348  )");
1349 
1350  // `root` element
1351  const auto root_element_xsd = R"(
1352  <xs:element name="root">
1353  <xs:complexType>
1354  <xs:sequence>
1355  <xs:choice minOccurs="0" maxOccurs="unbounded">
1356  <xs:element ref="include"/>
1357  <xs:element ref="BehaviorTree"/>
1358  </xs:choice>
1359  <xs:element ref="TreeNodesModel" minOccurs="0" maxOccurs="1"/>
1360  </xs:sequence>
1361  <xs:attribute name="BTCPP_format" type="xs:string" use="required"/>
1362  <xs:attribute name="main_tree_to_execute" type="xs:string" use="optional"/>
1363  </xs:complexType>
1364  </xs:element>
1365  )";
1366  parse_and_insert(schema_element, root_element_xsd);
1367 
1368  // Group definition for a single node of any of the existing node types.
1369  XMLElement* one_node_group = doc.NewElement("xs:group");
1370  {
1371  one_node_group->SetAttribute("name", "oneNodeGroup");
1372  std::ostringstream xsd;
1373  xsd << "<xs:choice>";
1374  for(const auto& [registration_id, model] : ordered_models)
1375  {
1376  xsd << "<xs:element name=\"" << registration_id << "\" type=\"" << registration_id
1377  << "Type\"/>";
1378  }
1379  xsd << "</xs:choice>";
1380  parse_and_insert(one_node_group, xsd.str().c_str());
1381  schema_element->InsertEndChild(one_node_group);
1382  }
1383 
1384  // `include` element
1385  parse_and_insert(schema_element, R"(
1386  <xs:element name="include">
1387  <xs:complexType>
1388  <xs:attribute name="path" type="xs:string" use="required"/>
1389  <xs:attribute name="ros_pkg" type="xs:string" use="optional"/>
1390  </xs:complexType>
1391  </xs:element>
1392  )");
1393 
1394  // `BehaviorTree` element
1395  parse_and_insert(schema_element, R"(
1396  <xs:element name="BehaviorTree">
1397  <xs:complexType>
1398  <xs:group ref="oneNodeGroup"/>
1399  <xs:attribute name="ID" type="xs:string" use="required"/>
1400  </xs:complexType>
1401  </xs:element>
1402  )");
1403 
1404  // `TreeNodesModel` element
1405  parse_and_insert(schema_element, R"(
1406  <xs:element name="TreeNodesModel">
1407  <xs:complexType>
1408  <xs:group ref="treeNodesModelNodeGroup" minOccurs="0" maxOccurs="unbounded"/>
1409  </xs:complexType>
1410  </xs:element>
1411  )");
1412 
1413  // Definitions for all node types.
1414  for(const auto& [registration_id, model] : ordered_models)
1415  {
1416  XMLElement* type = doc.NewElement("xs:complexType");
1417  type->SetAttribute("name", (model->registration_ID + "Type").c_str());
1418  if((model->type == NodeType::ACTION) or (model->type == NodeType::CONDITION) or
1419  (model->type == NodeType::SUBTREE))
1420  {
1421  /* No children, nothing to add. */
1422  }
1423  else if(model->type == NodeType::DECORATOR)
1424  {
1425  /* One child. */
1426  // <xs:group ref="oneNodeGroup" minOccurs="1" maxOccurs="1"/>
1427  XMLElement* group = doc.NewElement("xs:group");
1428  group->SetAttribute("ref", "oneNodeGroup");
1429  group->SetAttribute("minOccurs", "1");
1430  group->SetAttribute("maxOccurs", "1");
1431  type->InsertEndChild(group);
1432  }
1433  else
1434  {
1435  /* NodeType::CONTROL. */
1436  // TODO: check the code, the doc says 1..N but why not 0..N?
1437  // <xs:group ref="oneNodeGroup" minOccurs="0" maxOccurs="unbounded"/>
1438  XMLElement* group = doc.NewElement("xs:group");
1439  group->SetAttribute("ref", "oneNodeGroup");
1440  group->SetAttribute("minOccurs", "0");
1441  group->SetAttribute("maxOccurs", "unbounded");
1442  type->InsertEndChild(group);
1443  }
1444  XMLElement* common_attr_group = doc.NewElement("xs:attributeGroup");
1445  common_attr_group->SetAttribute("ref", "commonAttributeGroup");
1446  type->InsertEndChild(common_attr_group);
1447  for(const auto& [port_name, port_info] : model->ports)
1448  {
1449  XMLElement* attr = doc.NewElement("xs:attribute");
1450  attr->SetAttribute("name", port_name.c_str());
1451  const auto xsd_attribute_type = xsdAttributeType(port_info);
1452  if(not xsd_attribute_type.empty())
1453  {
1454  attr->SetAttribute("type", xsd_attribute_type.c_str());
1455  }
1456  if(not port_info.defaultValue().empty())
1457  {
1458  attr->SetAttribute("default", port_info.defaultValueString().c_str());
1459  }
1460  else
1461  {
1462  attr->SetAttribute("use", "required");
1463  }
1464  type->InsertEndChild(attr);
1465  }
1466  if(model->registration_ID == "SubTree")
1467  {
1468  parse_and_insert(type, R"(
1469  <xs:attribute name="ID" type="xs:string" use="required"/>
1470  <xs:anyAttribute processContents="skip"/>
1471  )");
1472  }
1473  schema_element->InsertEndChild(type);
1474  }
1475 
1476  XMLPrinter printer;
1477  doc.Print(&printer);
1478  return std::string(printer.CStr(), size_t(printer.CStrSize() - 1));
1479 }
1480 
1481 Tree buildTreeFromText(const BehaviorTreeFactory& factory, const std::string& text,
1482  const Blackboard::Ptr& blackboard)
1483 {
1484  XMLParser parser(factory);
1485  parser.loadFromText(text);
1486  return parser.instantiateTree(blackboard);
1487 }
1488 
1489 Tree buildTreeFromFile(const BehaviorTreeFactory& factory, const std::string& filename,
1490  const Blackboard::Ptr& blackboard)
1491 {
1492  XMLParser parser(factory);
1493  parser.loadFromFile(filename);
1494  return parser.instantiateTree(blackboard);
1495 }
1496 
1497 std::string WriteTreeToXML(const Tree& tree, bool add_metadata, bool add_builtin_models)
1498 {
1499  XMLDocument doc;
1500 
1501  XMLElement* rootXML = doc.NewElement("root");
1502  rootXML->SetAttribute("BTCPP_format", 4);
1503  doc.InsertFirstChild(rootXML);
1504 
1505  addTreeToXML(tree, doc, rootXML, add_metadata, add_builtin_models);
1506 
1507  XMLPrinter printer;
1508  doc.Print(&printer);
1509  return std::string(printer.CStr(), size_t(printer.CStrSize() - 1));
1510 }
1511 
1512 } // namespace BT
BT::PortInfo
Definition: basic_types.h:392
BT
Definition: ex01_wrap_legacy.cpp:29
BT::PortInfo::setDescription
void setDescription(StringView description)
Definition: basic_types.cpp:401
BT::BehaviorTreeFactory::builtinNodes
const std::set< std::string > & builtinNodes() const
List of builtin IDs.
Definition: bt_factory.cpp:390
BT::demangle
std::string demangle(char const *name)
Definition: demangle_util.h:74
tinyxml2::XMLDocument::Error
bool Error() const
Return true if there was an error parsing the document.
Definition: tinyxml2.h:1881
BT::PortDirection::INOUT
@ INOUT
BT::TreeNodeManifest::ports
PortsList ports
Definition: tree_node.h:39
BT::TreeNode::UID
uint16_t UID() const
Definition: tree_node.cpp:330
tinyxml2::XMLNode::InsertFirstChild
XMLNode * InsertFirstChild(XMLNode *addThis)
Definition: tinyxml2.cpp:925
BT::PreCond
PreCond
Definition: tree_node.h:45
ros::package::getPath
ROSLIB_DECL std::string getPath(const std::string &package_name)
BT::Tree::getUID
uint16_t getUID()
Definition: bt_factory.cpp:633
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:589
BT::NodeConfig::pre_conditions
std::map< PreCond, std::string > pre_conditions
Definition: tree_node.h:97
BT::XMLParser::loadFromText
void loadFromText(const std::string &xml_text, bool add_includes=true) override
Definition: xml_parsing.cpp:164
BT::PortInfo::defaultValueString
const std::string & defaultValueString() const
Definition: basic_types.cpp:416
BT::TreeNode::config
const NodeConfig & config() const
Definition: tree_node.cpp:345
BT::PortInfo::defaultValue
const Any & defaultValue() const
Definition: basic_types.cpp:411
tinyxml2::XMLComment
Definition: tinyxml2.h:1031
BT::NodeType::DECORATOR
@ DECORATOR
BT::NodeType::CONDITION
@ CONDITION
BT::XMLParser::PImpl::factory
const BehaviorTreeFactory & factory
Definition: xml_parsing.cpp:108
BT::StringView
std::string_view StringView
Definition: basic_types.h:59
BT::NodeConfig::path
std::string path
Definition: tree_node.h:95
BT::NodeConfig::input_ports
PortsRemapping input_ports
Definition: tree_node.h:83
BT::XMLParser::PImpl::loadSubtreeModel
void loadSubtreeModel(const XMLElement *xml_root)
Definition: xml_parsing.cpp:184
BT::PreCond::COUNT_
@ COUNT_
BT::SubtreeModel::ports
std::unordered_map< std::string, BT::PortInfo > ports
Definition: xml_parsing.cpp:85
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:174
BT::TreeNode
Abstract base class for Behavior Tree Nodes.
Definition: tree_node.h:118
BT::PortInfo::setDefaultValue
void setDefaultValue(const T &default_value)
Definition: basic_types.h:408
BT::Tree
Struct used to store a tree. If this object goes out of scope, the tree is destroyed.
Definition: bt_factory.h:91
tinyxml2::XMLDocument::LoadFile
XMLError LoadFile(const char *filename)
Definition: tinyxml2.cpp:2312
BT::XMLParser::PImpl::suffix_count
int suffix_count
Definition: xml_parsing.cpp:113
BT::NodeType::SUBTREE
@ SUBTREE
BT::Tree::manifests
std::unordered_map< std::string, TreeNodeManifest > manifests
Definition: bt_factory.h:105
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::TreeNodeManifest::type
NodeType type
Definition: tree_node.h:37
BT::TreeNode::Ptr
std::shared_ptr< TreeNode > Ptr
Definition: tree_node.h:121
BT::DecoratorNode
Definition: decorator_node.h:8
manifest
string manifest
BT::XMLParser::operator=
XMLParser & operator=(const XMLParser &other)=delete
BT::LogicError
Definition: exceptions.h:45
tinyxml2::XMLDocument::NewElement
XMLElement * NewElement(const char *name)
Definition: tinyxml2.cpp:2239
BT::PortDirection::OUTPUT
@ OUTPUT
BT::XMLParser::PImpl::createNodeFromXML
TreeNode::Ptr createNodeFromXML(const XMLElement *element, const Blackboard::Ptr &blackboard, const TreeNode::Ptr &node_parent, const std::string &prefix_path, Tree &output_tree)
Definition: xml_parsing.cpp:594
BT::BehaviorTreeFactory::manifests
const std::unordered_map< std::string, TreeNodeManifest > & manifests() const
Manifests of all the registered TreeNodes.
Definition: bt_factory.cpp:385
BT::SubTreeNode::setSubtreeID
void setSubtreeID(const std::string &ID)
Definition: subtree_node.h:61
BT::WriteTreeToXML
std::string WriteTreeToXML(const Tree &tree, bool add_metadata, bool add_builtin_models)
WriteTreeToXML create a string that contains the XML that corresponds to a given tree....
Definition: xml_parsing.cpp:1497
BT::Tree::Subtree::Ptr
std::shared_ptr< Subtree > Ptr
Definition: bt_factory.h:97
detail::void
j template void())
Definition: json.hpp:4893
tinyxml2::XMLAttribute
Definition: tinyxml2.h:1140
BT::TreeNode::registrationName
const std::string & registrationName() const
registrationName is the ID used by BehaviorTreeFactory to create an instance.
Definition: tree_node.cpp:340
BT::XMLParser::PImpl::loadDocImpl
void loadDocImpl(XMLDocument *doc, bool add_includes)
Definition: xml_parsing.cpp:228
BT::addNodeModelToXML
void addNodeModelToXML(const TreeNodeManifest &model, XMLDocument &doc, XMLElement *model_root)
Definition: xml_parsing.cpp:1026
BT::XMLParser::_p
std::unique_ptr< PImpl > _p
Definition: xml_parsing.h:42
BT::Blackboard::Ptr
std::shared_ptr< Blackboard > Ptr
Definition: blackboard.h:35
tinyxml2::XMLPrinter::CStr
const char * CStr() const
Definition: tinyxml2.h:2306
BT::NodeConfig::blackboard
Blackboard::Ptr blackboard
Definition: tree_node.h:79
tinyxml2::XMLElement::FirstAttribute
const XMLAttribute * FirstAttribute() const
Return the first attribute in the list.
Definition: tinyxml2.h:1514
lexy::count
constexpr auto count
Sink that counts all arguments.
Definition: fold.hpp:88
BT::NodeType::UNDEFINED
@ UNDEFINED
BT::TreeNodeManifest::registration_ID
std::string registration_ID
Definition: tree_node.h:38
tinyxml2::XMLPrinter::CStrSize
int CStrSize() const
Definition: tinyxml2.h:2314
BT::XMLParser::PImpl::getPortsRecursively
void getPortsRecursively(const XMLElement *element, std::vector< std::string > &output_ports)
Definition: xml_parsing.cpp:1004
BT::NodeType::ACTION
@ ACTION
lexyd::bit::_
constexpr auto _
Matches any bit.
Definition: bits.hpp:91
BT::XMLParser::PImpl::tree_roots
std::map< std::string, const XMLElement * > tree_roots
Definition: xml_parsing.cpp:106
BT::Any::empty
bool empty() const noexcept
Definition: safe_any.hpp:207
BT::StrEqual
auto StrEqual
Definition: xml_parsing.cpp:79
BT::convertFromString< bool >
bool convertFromString< bool >(StringView str)
Definition: basic_types.cpp:253
BT::Tree::initialize
void initialize()
Definition: bt_factory.cpp:550
lexy::buffer
buffer(const CharT *, const CharT *) -> buffer< deduce_encoding< CharT >>
tinyxml2::XMLDocument::ErrorStr
const char * ErrorStr() const
Definition: tinyxml2.cpp:2501
BT::XMLParser::instantiateTree
Tree instantiateTree(const Blackboard::Ptr &root_blackboard, std::string main_tree_to_execute={}) override
Definition: xml_parsing.cpp:550
tinyxml2::XMLDeclaration
Definition: tinyxml2.h:1070
BT::XMLParser::XMLParser
XMLParser(const BehaviorTreeFactory &factory)
Definition: xml_parsing.cpp:135
BT::XMLParser::PImpl::current_path
std::filesystem::path current_path
Definition: xml_parsing.cpp:110
BT::PostCond
PostCond
Definition: tree_node.h:55
lexy_ext::child
auto child(const lexy::parse_tree< Reader, TokenKind, MemoryResource > &tree, typename lexy::parse_tree< Reader, TokenKind, MemoryResource >::node node, Predicate predicate) -> std::optional< typename lexy::parse_tree< Reader, TokenKind, MemoryResource >::node >
Returns the first child that matches predicate, if there is any.
Definition: parse_tree_algorithm.hpp:244
BT::NodeConfig::uid
uint16_t uid
Definition: tree_node.h:90
BT::RuntimeError
Definition: exceptions.h:58
BT::TreeNodeManifest
This information is used mostly by the XMLParser.
Definition: tree_node.h:35
tinyxml2::XMLElement
Definition: tinyxml2.h:1264
BT::addTreeToXML
void addTreeToXML(const Tree &tree, XMLDocument &doc, XMLElement *rootXML, bool add_metadata, bool add_builtin_models)
Definition: xml_parsing.cpp:1082
BT::XMLParser::PImpl::opened_documents
std::list< std::unique_ptr< XMLDocument > > opened_documents
Definition: xml_parsing.cpp:105
BT::buildTreeFromFile
Tree buildTreeFromFile(const BehaviorTreeFactory &factory, const std::string &filename, const Blackboard::Ptr &blackboard)
Definition: xml_parsing.cpp:1489
demangle_util.h
BT::convertFromString< NodeType >
NodeType convertFromString< NodeType >(StringView str)
Definition: basic_types.cpp:302
tinyxml2::XMLDocument::RootElement
XMLElement * RootElement()
Definition: tinyxml2.h:1810
BT::XMLParser::PImpl::recursivelyCreateSubtree
void recursivelyCreateSubtree(const std::string &tree_ID, const std::string &tree_path, const std::string &prefix_path, Tree &output_tree, Blackboard::Ptr blackboard, const TreeNode::Ptr &root_node)
Definition: xml_parsing.cpp:859
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::PortDirection::INPUT
@ INPUT
BT::TypeInfo::type
const std::type_index & type() const
Definition: basic_types.cpp:373
BT::BehaviorTreeFactory
The BehaviorTreeFactory is used to create instances of a TreeNode at run-time.
Definition: bt_factory.h:205
BT::IsAllowedPortName
bool IsAllowedPortName(StringView str)
Definition: basic_types.cpp:421
package.h
BT::StrCat
std::string StrCat()
Definition: strcat.hpp:46
BT::Blackboard::create
static Blackboard::Ptr create(Blackboard::Ptr parent={})
Definition: blackboard.h:63
BT::NodeConfig::manifest
const TreeNodeManifest * manifest
Definition: tree_node.h:87
BT::TreeNode::name
const std::string & name() const
Name of the instance, not the type.
Definition: tree_node.cpp:296
BT::PortInfo::direction
PortDirection direction() const
Definition: basic_types.cpp:368
BT::PortsRemapping
std::unordered_map< std::string, std::string > PortsRemapping
Definition: tree_node.h:43
BT::TreeNode::getRemappedKey
static Expected< StringView > getRemappedKey(StringView port_name, StringView remapped_port)
Definition: tree_node.cpp:405
BT::XMLParser::PImpl::subtree_models
std::map< std::string, SubtreeModel > subtree_models
Definition: xml_parsing.cpp:111
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
tinyxml2::XMLDocument::Print
void Print(XMLPrinter *streamer=0) const
Definition: tinyxml2.cpp:2446
BT::XMLParser::PImpl::clear
void clear()
Definition: xml_parsing.cpp:119
BT::XMLParser::PImpl::PImpl
PImpl(const BehaviorTreeFactory &fact)
Definition: xml_parsing.cpp:115
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:1481
BT::PostCond::COUNT_
@ COUNT_
BT::TreeNodeManifest::metadata
KeyValueVector metadata
Definition: tree_node.h:40
BT::NodeType::CONTROL
@ CONTROL
BT::NodeConfig::post_conditions
std::map< PostCond, std::string > post_conditions
Definition: tree_node.h:98
std
Definition: std.hpp:30
lexyd::ascii::control
constexpr auto control
Definition: ascii.hpp:42
BT::NodeConfig::output_ports
PortsRemapping output_ports
Definition: tree_node.h:85
lexy::string_input
string_input(const CharT *begin, const CharT *end) -> string_input< deduce_encoding< CharT >>
BT::VerifyXML
void VerifyXML(const std::string &xml_text, const std::unordered_map< std::string, NodeType > &registered_nodes)
tinyxml2::XMLDocument
Definition: tinyxml2.h:1716
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:16
BT::XMLParser::PImpl
Definition: xml_parsing.cpp:88
BT::NodeConfig
Definition: tree_node.h:73
tinyxml2.h
BT::TreeNode::isBlackboardPointer
static bool isBlackboardPointer(StringView str, StringView *stripped_pointer=nullptr)
Check a string and return true if it matches the pattern: {...}.
Definition: tree_node.cpp:369
blackboard.h
tinyxml2::XMLNode::InsertEndChild
XMLNode * InsertEndChild(XMLNode *addThis)
Definition: tinyxml2.cpp:895
tree_node.h
xml_text
static const char * xml_text
Definition: ex01_wrap_legacy.cpp:52
BT::writeTreeXSD
std::string writeTreeXSD(const BehaviorTreeFactory &factory)
writeTreeXSD generates an XSD for the nodes defined in the factory
Definition: xml_parsing.cpp:1210
BT::SubTreeNode
The SubTreeNode is a way to wrap an entire Subtree, creating a separated BlackBoard....
Definition: subtree_node.h:52
BT::ControlNode
Definition: control_node.h:21
BT::XMLParser::~XMLParser
~XMLParser() override
Definition: xml_parsing.cpp:149
BT::PortInfo::description
const std::string & description() const
Definition: basic_types.cpp:406
tinyxml2::XMLDocument::NewDeclaration
XMLDeclaration * NewDeclaration(const char *text=0)
Definition: tinyxml2.cpp:2263
BT::writeTreeNodesModelXML
std::string writeTreeNodesModelXML(const BehaviorTreeFactory &factory, bool include_builtin=false)
writeTreeNodesModelXML generates an XMl that contains the manifests in the <TreeNodesModel>
Definition: xml_parsing.cpp:1178
tinyxml2::XMLDocument::Parse
XMLError Parse(const char *xml, size_t nBytes=static_cast< size_t >(-1))
Definition: tinyxml2.cpp:2415
BT::toStr
std::string toStr(const T &value)
toStr is the reverse operation of convertFromString.
Definition: basic_types.h:252
BT::SubtreeModel
Definition: xml_parsing.cpp:83
tinyxml2::XMLDocument::NewComment
XMLComment * NewComment(const char *comment)
Definition: tinyxml2.cpp:2247
BT::TypeInfo::isStronglyTyped
bool isStronglyTyped() const
Definition: basic_types.h:376
BT::TreeNode::stripBlackboardPointer
static StringView stripBlackboardPointer(StringView str)
Definition: tree_node.cpp:395
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_v4
Author(s): Davide Faconti
autogenerated on Fri Jun 28 2024 02:20:08