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