gtest_ports.cpp
Go to the documentation of this file.
1 #include <gtest/gtest.h>
6 
7 using namespace BT;
8 
10 {
11 public:
12  NodeWithPorts(const std::string& name, const NodeConfig& config)
13  : SyncActionNode(name, config)
14  {
15  std::cout << "ctor" << std::endl;
16  }
17 
18  NodeStatus tick() override
19  {
20  int val_A = 0;
21  int val_B = 0;
22  if(!getInput("in_port_A", val_A))
23  {
24  throw RuntimeError("missing input [in_port_A]");
25  }
26  if(!getInput("in_port_B", val_B))
27  {
28  throw RuntimeError("missing input [in_port_B]");
29  }
30 
31  if(val_A == 42 && val_B == 66)
32  {
33  return NodeStatus::SUCCESS;
34  }
35  return NodeStatus::FAILURE;
36  }
37 
39  {
40  return { BT::InputPort<int>("in_port_A", 42, "magic_number"),
41  BT::InputPort<int>("in_port_B") };
42  }
43 };
44 
45 TEST(PortTest, WrongNodeConfig)
46 {
47  NodeConfig config;
48  config.input_ports["in_port_A"] = "42";
49  // intentionally missing:
50  // config.input_ports["in_port_B"] = "69";
51  NodeWithPorts node("will_fail", config);
52  ASSERT_ANY_THROW(node.tick());
53 }
54 
55 TEST(PortTest, DefaultPorts)
56 {
57  std::string xml_txt = R"(
58  <root BTCPP_format="4" >
59  <BehaviorTree ID="MainTree">
60  <NodeWithPorts in_port_B="66" />
61  </BehaviorTree>
62  </root>)";
63 
64  BehaviorTreeFactory factory;
65  factory.registerNodeType<NodeWithPorts>("NodeWithPorts");
66  auto tree = factory.createTreeFromText(xml_txt);
67  NodeStatus status = tree.tickWhileRunning();
68  ASSERT_EQ(status, NodeStatus::SUCCESS);
69 }
70 
71 TEST(PortTest, MissingPort)
72 {
73  std::string xml_txt = R"(
74  <root BTCPP_format="4" >
75  <BehaviorTree ID="MainTree">
76  <NodeWithPorts/>
77  </BehaviorTree>
78  </root>)";
79 
80  BehaviorTreeFactory factory;
81  factory.registerNodeType<NodeWithPorts>("NodeWithPorts");
82  auto tree = factory.createTreeFromText(xml_txt);
83  ASSERT_ANY_THROW(tree.tickWhileRunning());
84 }
85 
86 TEST(PortTest, WrongPort)
87 {
88  std::string xml_txt = R"(
89  <root BTCPP_format="4" >
90  <BehaviorTree ID="MainTree">
91  <NodeWithPorts da_port="66" />
92  </BehaviorTree>
93  </root>)";
94 
95  BehaviorTreeFactory factory;
96  factory.registerNodeType<NodeWithPorts>("NodeWithPorts");
97 
98  EXPECT_ANY_THROW(auto tree = factory.createTreeFromText(xml_txt));
99 }
100 
101 TEST(PortTest, Descriptions)
102 {
103  std::string xml_txt = R"(
104  <root BTCPP_format="4" >
105  <BehaviorTree ID="MainTree" _description="this is my tree" >
106  <Sequence>
107  <NodeWithPorts name="first" in_port_B="66" _description="this is my action" />
108  <SubTree ID="mySubTree" name="second" _description="this is a subtree"/>
109  </Sequence>
110  </BehaviorTree>
111 
112  <BehaviorTree ID="mySubTree" _description="this is a subtree" >
113  <NodeWithPorts name="third" in_port_B="99" />
114  </BehaviorTree>
115 
116  </root>)";
117 
118  BehaviorTreeFactory factory;
119  factory.registerNodeType<NodeWithPorts>("NodeWithPorts");
120 
121  factory.registerBehaviorTreeFromText(xml_txt);
122  auto tree = factory.createTree("MainTree");
123 
124  NodeStatus status = tree.tickWhileRunning();
125  while(status == NodeStatus::RUNNING)
126  {
127  status = tree.tickWhileRunning();
128  }
129 
130  ASSERT_EQ(status, NodeStatus::FAILURE); // failure because in_port_B="99"
131 }
132 
133 TEST(PortsTest, NonPorts)
134 {
135  std::string xml_txt =
136  R"(
137  <root BTCPP_format="4" >
138  <BehaviorTree ID="MainTree">
139  <Action ID="NodeWithPorts" name="NodeWithPortsName" in_port_B="66" _not_da_port="whateva" _skipIf="true" />
140  </BehaviorTree>
141  </root>)";
142 
143  BehaviorTreeFactory factory;
144  factory.registerNodeType<NodeWithPorts>("NodeWithPorts");
145 
146  auto tree = factory.createTreeFromText(xml_txt);
147 
148  const TreeNode* root = tree.rootNode();
149  ASSERT_NE(root, nullptr);
150  ASSERT_EQ(root->type(), NodeType::ACTION);
151 
152  EXPECT_EQ(root->config().other_attributes.size(), 1);
153  ASSERT_TRUE(root->config().other_attributes.contains("_not_da_port"));
154  EXPECT_EQ(root->config().other_attributes.at("_not_da_port"), "whateva");
155 }
156 
157 struct MyType
158 {
159  std::string value;
160 };
161 
162 class NodeInPorts : public SyncActionNode
163 {
164 public:
165  NodeInPorts(const std::string& name, const NodeConfig& config)
166  : SyncActionNode(name, config)
167  {}
168 
169  NodeStatus tick() override
170  {
171  int val_A = 0;
172  MyType val_B;
173  if(getInput("int_port", val_A) && getInput("any_port", val_B))
174  {
176  }
177  return NodeStatus::FAILURE;
178  }
179 
180  static PortsList providedPorts()
181  {
182  return { BT::InputPort<int>("int_port"), BT::InputPort<MyType>("any_port") };
183  }
184 };
185 
186 class NodeOutPorts : public SyncActionNode
187 {
188 public:
189  NodeOutPorts(const std::string& name, const NodeConfig& config)
190  : SyncActionNode(name, config)
191  {}
192 
193  NodeStatus tick() override
194  {
195  return NodeStatus::SUCCESS;
196  }
197 
198  static PortsList providedPorts()
199  {
200  return { BT::OutputPort<int>("int_port"), BT::OutputPort<MyType>("any_port") };
201  }
202 };
203 
204 TEST(PortTest, EmptyPort)
205 {
206  std::string xml_txt = R"(
207  <root BTCPP_format="4" >
208  <BehaviorTree ID="MainTree">
209  <Sequence>
210  <NodeInPorts int_port="{ip}" any_port="{ap}" />
211  <NodeOutPorts int_port="{ip}" any_port="{ap}" />
212  </Sequence>
213  </BehaviorTree>
214  </root>)";
215 
216  BehaviorTreeFactory factory;
217  factory.registerNodeType<NodeOutPorts>("NodeOutPorts");
218  factory.registerNodeType<NodeInPorts>("NodeInPorts");
219 
220  auto tree = factory.createTreeFromText(xml_txt);
221 
222  NodeStatus status = tree.tickWhileRunning();
223  // expect failure because port is not set yet
224  ASSERT_EQ(status, NodeStatus::FAILURE);
225 }
226 
227 class IllegalPorts : public SyncActionNode
228 {
229 public:
230  IllegalPorts(const std::string& name, const NodeConfig& config)
231  : SyncActionNode(name, config)
232  {}
233 
234  NodeStatus tick() override
235  {
236  return NodeStatus::SUCCESS;
237  }
238 
239  static PortsList providedPorts()
240  {
241  return { BT::InputPort<std::string>("name") };
242  }
243 };
244 
245 TEST(PortTest, IllegalPorts)
246 {
247  BehaviorTreeFactory factory;
248  ASSERT_ANY_THROW(factory.registerNodeType<IllegalPorts>("nope"));
249 }
250 
252 {
253 public:
254  ActionVectorDoubleIn(const std::string& name, const NodeConfig& config,
255  std::vector<double>* states)
256  : SyncActionNode(name, config), states_(states)
257  {}
258 
259  NodeStatus tick() override
260  {
261  getInput("states", *states_);
262  return NodeStatus::SUCCESS;
263  }
264 
265  static PortsList providedPorts()
266  {
267  return { BT::InputPort<std::vector<double>>("states") };
268  }
269 
270 private:
271  std::vector<double>* states_;
272 };
273 
274 TEST(PortTest, SubtreeStringInput_Issue489)
275 {
276  std::string xml_txt = R"(
277  <root BTCPP_format="4" >
278  <BehaviorTree ID="Main">
279  <SubTree ID="Subtree_A" states="3;7"/>
280  </BehaviorTree>
281 
282  <BehaviorTree ID="Subtree_A">
283  <ActionVectorDoubleIn states="{states}"/>
284  </BehaviorTree>
285  </root>)";
286 
287  std::vector<double> states;
288 
289  BehaviorTreeFactory factory;
290  factory.registerNodeType<ActionVectorDoubleIn>("ActionVectorDoubleIn", &states);
291 
292  factory.registerBehaviorTreeFromText(xml_txt);
293  auto tree = factory.createTree("Main");
294 
295  NodeStatus status = tree.tickWhileRunning();
296 
297  ASSERT_EQ(status, NodeStatus::SUCCESS);
298  ASSERT_EQ(2, states.size());
299  ASSERT_EQ(3, states[0]);
300  ASSERT_EQ(7, states[1]);
301 }
302 
304 {
305 public:
306  ActionVectorStringIn(const std::string& name, const NodeConfig& config,
307  std::vector<std::string>* states)
308  : SyncActionNode(name, config), states_(states)
309  {}
310 
311  NodeStatus tick() override
312  {
313  getInput("states", *states_);
314  return NodeStatus::SUCCESS;
315  }
316 
317  static PortsList providedPorts()
318  {
319  return { BT::InputPort<std::vector<std::string>>("states") };
320  }
321 
322 private:
323  std::vector<std::string>* states_;
324 };
325 
326 TEST(PortTest, SubtreeStringInput_StringVector)
327 {
328  std::string xml_txt = R"(
329  <root BTCPP_format="4" >
330  <BehaviorTree ID="Main">
331  <ActionVectorStringIn states="hello;world;with spaces"/>
332  </BehaviorTree>
333  </root>)";
334 
335  std::vector<std::string> states;
336 
337  BehaviorTreeFactory factory;
338  factory.registerNodeType<ActionVectorStringIn>("ActionVectorStringIn", &states);
339 
340  factory.registerBehaviorTreeFromText(xml_txt);
341  auto tree = factory.createTree("Main");
342 
343  NodeStatus status = tree.tickWhileRunning();
344 
345  ASSERT_EQ(status, NodeStatus::SUCCESS);
346  ASSERT_EQ(3, states.size());
347  ASSERT_EQ("hello", states[0]);
348  ASSERT_EQ("world", states[1]);
349  ASSERT_EQ("with spaces", states[2]);
350 }
351 
352 struct Point2D
353 {
354  int x = 0;
355  int y = 0;
356  bool operator==(const Point2D& other) const
357  {
358  return x == other.x && y == other.y;
359  }
360  bool operator!=(const Point2D& other) const
361  {
362  return !(*this == other);
363  }
364 };
365 
366 template <>
367 [[nodiscard]] Point2D BT::convertFromString<Point2D>(StringView str)
368 {
369  if(StartWith(str, "json:"))
370  {
371  str.remove_prefix(5);
372  return convertFromJSON<Point2D>(str);
373  }
374  const auto parts = BT::splitString(str, ',');
375  if(parts.size() != 2)
376  {
377  throw BT::RuntimeError("invalid input)");
378  }
379  int x = convertFromString<int>(parts[0]);
380  int y = convertFromString<int>(parts[1]);
381  return { x, y };
382 }
383 
384 template <>
385 [[nodiscard]] std::string BT::toStr<Point2D>(const Point2D& point)
386 {
387  return std::to_string(point.x) + "," + std::to_string(point.y);
388 }
389 
391 {
392  add_field("x", &point.x);
393  add_field("y", &point.y);
394 }
395 
396 class DefaultTestAction : public SyncActionNode
397 {
398 public:
399  DefaultTestAction(const std::string& name, const NodeConfig& config)
400  : SyncActionNode(name, config)
401  {}
402 
403  NodeStatus tick() override
404  {
405  const int answer = getInput<int>("answer").value();
406  if(answer != 42)
407  {
408  return NodeStatus::FAILURE;
409  }
410 
411  const std::string greet = getInput<std::string>("greeting").value();
412  if(greet != "hello")
413  {
414  return NodeStatus::FAILURE;
415  }
416 
417  const Point2D point = getInput<Point2D>("pos").value();
418  if(point.x != 1 || point.y != 2)
419  {
420  return NodeStatus::FAILURE;
421  }
422 
423  return NodeStatus::SUCCESS;
424  }
425 
426  static PortsList providedPorts()
427  {
428  return { BT::InputPort<int>("answer", 42, "the answer"),
429  BT::InputPort<std::string>("greeting", "hello", "be polite"),
430  BT::InputPort<Point2D>("pos", Point2D{ 1, 2 }, "where") };
431  }
432 };
433 
434 TEST(PortTest, DefaultInput)
435 {
436  std::string xml_txt = R"(
437  <root BTCPP_format="4" >
438  <BehaviorTree>
439  <DefaultTestAction/>
440  </BehaviorTree>
441  </root>)";
442 
443  BehaviorTreeFactory factory;
444  factory.registerNodeType<DefaultTestAction>("DefaultTestAction");
445  auto tree = factory.createTreeFromText(xml_txt);
446  auto status = tree.tickOnce();
447  ASSERT_EQ(status, NodeStatus::SUCCESS);
448 }
449 
450 class GetAny : public SyncActionNode
451 {
452 public:
453  GetAny(const std::string& name, const NodeConfig& config) : SyncActionNode(name, config)
454  {}
455 
456  NodeStatus tick() override
457  {
458  // case 1: the port is Any, but we can cast dirrectly to string
459  auto res_str = getInput<std::string>("val_str");
460  // case 2: the port is Any, and we retrieve an Any (to be casted later)
461  auto res_int = getInput<BT::Any>("val_int");
462 
463  // case 3: port is double and we get a double
464  auto res_real_A = getInput<double>("val_real");
465  // case 4: port is double and we get an Any
466  auto res_real_B = getInput<BT::Any>("val_real");
467 
468  bool expected = res_str.value() == "hello" && res_int->cast<int>() == 42 &&
469  res_real_A.value() == 3.14 && res_real_B->cast<double>() == 3.14;
470 
471  return expected ? NodeStatus::SUCCESS : NodeStatus::FAILURE;
472  }
473 
474  static PortsList providedPorts()
475  {
476  return { BT::InputPort<BT::Any>("val_str"), BT::InputPort<BT::Any>("val_int"),
477  BT::InputPort<double>("val_real") };
478  }
479 };
480 
481 class SetAny : public SyncActionNode
482 {
483 public:
484  SetAny(const std::string& name, const NodeConfig& config) : SyncActionNode(name, config)
485  {}
486 
487  NodeStatus tick() override
488  {
489  // check that the port can contain different types
490  setOutput("val_str", BT::Any(1.0));
491  setOutput("val_str", BT::Any(1));
492  setOutput("val_str", BT::Any("hello"));
493 
494  setOutput("val_int", 42);
495  setOutput("val_real", 3.14);
496  return NodeStatus::SUCCESS;
497  }
498 
499  static PortsList providedPorts()
500  {
501  return { BT::OutputPort<BT::Any>("val_str"), BT::OutputPort<int>("val_int"),
502  BT::OutputPort<BT::Any>("val_real") };
503  }
504 };
505 
506 TEST(PortTest, AnyPort)
507 {
508  std::string xml_txt = R"(
509  <root BTCPP_format="4" >
510  <BehaviorTree>
511  <Sequence>
512  <SetAny val_str="{val_str}" val_int="{val_int}" val_real="{val_real}"/>
513  <GetAny val_str="{val_str}" val_int="{val_int}" val_real="{val_real}"/>
514  </Sequence>
515  </BehaviorTree>
516  </root>)";
517 
518  BehaviorTreeFactory factory;
519  factory.registerNodeType<SetAny>("SetAny");
520  factory.registerNodeType<GetAny>("GetAny");
521  auto tree = factory.createTreeFromText(xml_txt);
522  auto status = tree.tickOnce();
523  ASSERT_EQ(status, NodeStatus::SUCCESS);
524 }
525 
527 {
528 public:
529  NodeWithDefaultPoints(const std::string& name, const NodeConfig& config)
530  : SyncActionNode(name, config)
531  {}
532 
533  NodeStatus tick() override
534  {
535  Point2D pointA, pointB, pointC, pointD, pointE, input;
536 
537  if(!getInput("pointA", pointA) || pointA != Point2D{ 1, 2 })
538  {
539  throw std::runtime_error("failed pointA");
540  }
541  if(!getInput("pointB", pointB) || pointB != Point2D{ 3, 4 })
542  {
543  throw std::runtime_error("failed pointB");
544  }
545  if(!getInput("pointC", pointC) || pointC != Point2D{ 5, 6 })
546  {
547  throw std::runtime_error("failed pointC");
548  }
549  if(!getInput("pointD", pointD) || pointD != Point2D{ 7, 8 })
550  {
551  throw std::runtime_error("failed pointD");
552  }
553  if(!getInput("pointE", pointE) || pointE != Point2D{ 9, 10 })
554  {
555  throw std::runtime_error("failed pointE");
556  }
557  if(!getInput("input", input) || input != Point2D{ -1, -2 })
558  {
559  throw std::runtime_error("failed input");
560  }
561  return NodeStatus::SUCCESS;
562  }
563 
564  static PortsList providedPorts()
565  {
566  return { BT::InputPort<Point2D>("input", "no default value"),
567  BT::InputPort<Point2D>("pointA", Point2D{ 1, 2 }, "default value is [1,2]"),
568  BT::InputPort<Point2D>("pointB", "{point}",
569  "default value inside blackboard {point}"),
570  BT::InputPort<Point2D>("pointC", "5,6", "default value is [5,6]"),
571  BT::InputPort<Point2D>("pointD", "{=}",
572  "default value inside blackboard {pointD}"),
573  BT::InputPort<Point2D>("pointE", R"(json:{"x":9,"y":10})",
574  "default value is [9,10]") };
575  }
576 };
577 
578 TEST(PortTest, DefaultInputPoint2D)
579 {
580  std::string xml_txt = R"(
581  <root BTCPP_format="4" >
582  <BehaviorTree>
583  <NodeWithDefaultPoints input="-1,-2"/>
584  </BehaviorTree>
585  </root>)";
586 
588 
589  BehaviorTreeFactory factory;
590  factory.registerNodeType<NodeWithDefaultPoints>("NodeWithDefaultPoints");
591  auto tree = factory.createTreeFromText(xml_txt);
592 
593  tree.subtrees.front()->blackboard->set<Point2D>("point", Point2D{ 3, 4 });
594  tree.subtrees.front()->blackboard->set<Point2D>("pointD", Point2D{ 7, 8 });
595 
596  BT::NodeStatus status;
597  ASSERT_NO_THROW(status = tree.tickOnce());
598  ASSERT_EQ(status, NodeStatus::SUCCESS);
599 
600  std::cout << writeTreeNodesModelXML(factory) << std::endl;
601 }
602 
604 {
605 public:
606  NodeWithDefaultStrings(const std::string& name, const NodeConfig& config)
607  : SyncActionNode(name, config)
608  {}
609 
610  NodeStatus tick() override
611  {
612  std::string input, msgA, msgB, msgC;
613  if(!getInput("input", input) || input != "from XML")
614  {
615  throw std::runtime_error("failed input");
616  }
617  if(!getInput("msgA", msgA) || msgA != "hello")
618  {
619  throw std::runtime_error("failed msgA");
620  }
621  if(!getInput("msgB", msgB) || msgB != "ciao")
622  {
623  throw std::runtime_error("failed msgB");
624  }
625  if(!getInput("msgC", msgC) || msgC != "hola")
626  {
627  throw std::runtime_error("failed msgC");
628  }
629  return NodeStatus::SUCCESS;
630  }
631 
632  static PortsList providedPorts()
633  {
634  return { BT::InputPort<std::string>("input", "no default"),
635  BT::InputPort<std::string>("msgA", "hello", "default value is 'hello'"),
636  BT::InputPort<std::string>("msgB", "{msg}",
637  "default value inside blackboard {msg}"),
638  BT::InputPort<std::string>("msgC", "{=}",
639  "default value inside blackboard {msgC}") };
640  }
641 };
642 
643 TEST(PortTest, DefaultInputStrings)
644 {
645  std::string xml_txt = R"(
646  <root BTCPP_format="4" >
647  <BehaviorTree>
648  <NodeWithDefaultStrings input="from XML"/>
649  </BehaviorTree>
650  </root>)";
651 
652  BehaviorTreeFactory factory;
653  factory.registerNodeType<NodeWithDefaultStrings>("NodeWithDefaultStrings");
654  auto tree = factory.createTreeFromText(xml_txt);
655 
656  tree.subtrees.front()->blackboard->set<std::string>("msg", "ciao");
657  tree.subtrees.front()->blackboard->set<std::string>("msgC", "hola");
658 
659  BT::NodeStatus status;
660  ASSERT_NO_THROW(status = tree.tickOnce());
661  ASSERT_EQ(status, NodeStatus::SUCCESS);
662 
663  std::cout << writeTreeNodesModelXML(factory) << std::endl;
664 }
665 
666 struct TestStruct
667 {
668  int a;
669  double b;
670  std::string c;
671 };
672 
674 {
675 public:
676  NodeWithDefaultNullptr(const std::string& name, const NodeConfig& config)
677  : SyncActionNode(name, config)
678  {}
679 
680  NodeStatus tick() override
681  {
682  return NodeStatus::SUCCESS;
683  }
684 
685  static PortsList providedPorts()
686  {
687  return { BT::InputPort<std::shared_ptr<TestStruct>>("input", nullptr,
688  "default value is nullptr") };
689  }
690 };
691 
692 TEST(PortTest, Default_Issues_767)
693 {
694  using namespace BT;
695 
696  ASSERT_NO_THROW(auto p = InputPort<std::optional<Point2D>>("opt_A", std::nullopt,
697  "default nullopt"));
698  ASSERT_NO_THROW(auto p = InputPort<std::optional<std::string>>("opt_B", std::nullopt,
699  "default nullopt"));
700 
701  ASSERT_NO_THROW(
702  auto p = InputPort<std::shared_ptr<Point2D>>("ptr_A", nullptr, "default nullptr"));
703  ASSERT_NO_THROW(auto p = InputPort<std::shared_ptr<std::string>>("ptr_B", nullptr,
704  "default nullptr"));
705 }
706 
707 TEST(PortTest, DefaultWronglyOverriden)
708 {
709  BT::BehaviorTreeFactory factory;
710  factory.registerNodeType<NodeWithDefaultNullptr>("NodeWithDefaultNullptr");
711 
712  std::string xml_txt_wrong = R"(
713  <root BTCPP_format="4" >
714  <BehaviorTree>
715  <NodeWithDefaultNullptr input=""/>
716  </BehaviorTree>
717  </root>)";
718 
719  std::string xml_txt_correct = R"(
720  <root BTCPP_format="4" >
721  <BehaviorTree>
722  <NodeWithDefaultNullptr/>
723  </BehaviorTree>
724  </root>)";
725 
726  // this should throw, because we are NOT using the default,
727  // but overriding it with an empty string instead.
728  // See issue 768 for reference
729  ASSERT_ANY_THROW(auto tree = factory.createTreeFromText(xml_txt_wrong));
730  // This is correct
731  ASSERT_NO_THROW(auto tree = factory.createTreeFromText(xml_txt_correct));
732 }
NodeWithDefaultStrings
Definition: gtest_ports.cpp:598
BT
Definition: ex01_wrap_legacy.cpp:29
BT::Any
Definition: safe_any.hpp:36
BT::BehaviorTreeFactory::createTree
Tree createTree(const std::string &tree_name, Blackboard::Ptr blackboard=Blackboard::create())
Definition: bt_factory.cpp:421
BT::TreeNode::config
const NodeConfig & config() const
Definition: tree_node.cpp:351
basic_types.h
BT::StringView
std::string_view StringView
Definition: basic_types.h:59
BT::InputPort
std::pair< std::string, PortInfo > InputPort(StringView name, StringView description={})
Definition: basic_types.h:472
TestStruct
Definition: gtest_ports.cpp:661
BT::NodeConfig::input_ports
PortsRemapping input_ports
Definition: tree_node.h:92
TEST
TEST(PortTest, WrongNodeConfig)
Definition: gtest_ports.cpp:45
IllegalPorts
Definition: gtest_ports.cpp:222
BT::TreeNode
Abstract base class for Behavior Tree Nodes.
Definition: tree_node.h:131
Point2D
Definition: t12_default_ports.cpp:11
NodeWithDefaultNullptr
Definition: gtest_ports.cpp:668
bt_factory.h
MyType
Definition: gtest_ports.cpp:152
zmq::operator==
bool operator==(const detail::socket_base &a, const detail::socket_base &b) ZMQ_NOTHROW
Definition: 3rdparty/cppzmq/zmq.hpp:2139
ActionVectorStringIn
Definition: gtest_ports.cpp:298
BT::Tree::tickWhileRunning
NodeStatus tickWhileRunning(std::chrono::milliseconds sleep_time=std::chrono::milliseconds(10))
Definition: bt_factory.cpp:586
NodeWithPorts::tick
NodeStatus tick() override
Method to be implemented by the user.
Definition: gtest_ports.cpp:18
BT::PortsList
std::unordered_map< std::string, PortInfo > PortsList
Definition: basic_types.h:587
lexyd::nullopt
constexpr auto nullopt
Definition: option.hpp:50
BT::NodeStatus::FAILURE
@ FAILURE
BT::NodeType::ACTION
@ ACTION
BT::BehaviorTreeFactory::registerNodeType
void registerNodeType(const std::string &ID, const PortsList &ports, ExtraArgs... args)
Definition: bt_factory.h:326
NodeInPorts
Definition: gtest_ports.cpp:157
BT::BehaviorTreeFactory::createTreeFromText
Tree createTreeFromText(const std::string &text, Blackboard::Ptr blackboard=Blackboard::create())
createTreeFromText will parse the XML directly from string. The XML needs to contain either a single ...
Definition: bt_factory.cpp:384
ActionVectorDoubleIn
Definition: gtest_ports.cpp:246
BT::RuntimeError
Definition: exceptions.h:58
json_export.h
BT::TreeNode::type
virtual NodeType type() const =0
BT::splitString
std::vector< StringView > splitString(const StringView &strToSplit, char delimeter)
Definition: basic_types.cpp:349
DefaultTestAction
Definition: gtest_ports.cpp:391
BT::JsonExporter::get
static JsonExporter & get()
Definition: json_export.cpp:6
to_string
NLOHMANN_BASIC_JSON_TPL_DECLARATION std::string to_string(const NLOHMANN_BASIC_JSON_TPL &j)
user-defined to_string function for JSON values
Definition: json.hpp:24456
xml_parsing.h
BT::BehaviorTreeFactory
The BehaviorTreeFactory is used to create instances of a TreeNode at run-time.
Definition: bt_factory.h:209
BT::NodeStatus::SUCCESS
@ SUCCESS
NodeWithPorts
Definition: gtest_ports.cpp:9
NodeWithPorts::NodeWithPorts
NodeWithPorts(const std::string &name, const NodeConfig &config)
Definition: gtest_ports.cpp:12
BT::NodeStatus::RUNNING
@ RUNNING
BT::StartWith
bool StartWith(StringView str, StringView prefix)
Definition: basic_types.cpp:476
zmq::operator!=
bool operator!=(const detail::socket_base &a, const detail::socket_base &b) ZMQ_NOTHROW
Definition: 3rdparty/cppzmq/zmq.hpp:2143
BT::BehaviorTreeFactory::registerBehaviorTreeFromText
void registerBehaviorTreeFromText(const std::string &xml_text)
Definition: bt_factory.cpp:266
NodeWithDefaultPoints
Definition: t12_default_ports.cpp:55
BT_JSON_CONVERTER
BT_JSON_CONVERTER(Point2D, point)
Definition: gtest_ports.cpp:385
SetAny
Definition: gtest_ports.cpp:476
NodeWithPorts::providedPorts
static PortsList providedPorts()
Definition: gtest_ports.cpp:38
BT::JsonExporter::addConverter
void addConverter()
Definition: json_export.h:130
Point2D::x
int x
Definition: t12_default_ports.cpp:13
BT::NodeConfig
Definition: tree_node.h:82
NodeOutPorts
Definition: gtest_ports.cpp:181
BT::SyncActionNode
The SyncActionNode is an ActionNode that explicitly prevents the status RUNNING and doesn't require a...
Definition: action_node.h:52
Point2D::y
int y
Definition: t12_default_ports.cpp:14
BT::NodeStatus
NodeStatus
Definition: basic_types.h:33
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
lexyd::p
constexpr auto p
Parses the production.
Definition: production.hpp:127
GetAny
Definition: gtest_ports.cpp:445
BT::NodeConfig::other_attributes
NonPortAttributes other_attributes
Definition: tree_node.h:98


behaviortree_cpp_v4
Author(s): Davide Faconti
autogenerated on Wed Apr 16 2025 02:20:56