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


behaviortree_cpp_v4
Author(s): Davide Faconti
autogenerated on Fri Dec 13 2024 03:19:17