gtest_blackboard.cpp
Go to the documentation of this file.
1 /* Copyright (C) 2018-2023 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 <gtest/gtest.h>
16 
17 #include "../sample_nodes/dummy_nodes.h"
18 
19 using namespace BT;
20 
22 {
23 public:
24  BB_TestNode(const std::string& name, const NodeConfig& config)
25  : SyncActionNode(name, config)
26  {}
27 
29  {
30  int value = 0;
31  auto res = getInput<int>("in_port");
32  if(!res)
33  {
34  throw RuntimeError("BB_TestNode needs input: ", res.error());
35  }
36  value = res.value() * 2;
37  if(!setOutput("out_port", value))
38  {
39  throw RuntimeError("BB_TestNode failed output");
40  }
41  return NodeStatus::SUCCESS;
42  }
43 
45  {
46  return { BT::InputPort<int>("in_port"), BT::OutputPort<int>("out_port") };
47  }
48 };
49 
51 {
52 public:
53  BB_TypedTestNode(const std::string& name, const NodeConfig& config)
54  : SyncActionNode(name, config)
55  {}
56 
58  {
59  return NodeStatus::SUCCESS;
60  }
61 
63  {
64  return { BT::InputPort("input"),
65  BT::InputPort<int>("input_int"),
66  BT::InputPort<std::string>("input_string"),
67 
68  BT::OutputPort("output"),
69  BT::OutputPort<int>("output_int"),
70  BT::OutputPort<std::string>("output_string") };
71  }
72 };
73 
74 TEST(BlackboardTest, GetInputsFromBlackboard)
75 {
76  auto bb = Blackboard::create();
77 
78  NodeConfig config;
79  assignDefaultRemapping<BB_TestNode>(config);
80 
81  config.blackboard = bb;
82  bb->set("in_port", 11);
83 
84  BB_TestNode node("good_one", config);
85 
86  // this should read and write "my_entry" in tick()
87  node.executeTick();
88 
89  ASSERT_EQ(bb->get<int>("out_port"), 22);
90 }
91 
92 TEST(BlackboardTest, BasicRemapping)
93 {
94  auto bb = Blackboard::create();
95 
96  NodeConfig config;
97 
98  config.blackboard = bb;
99  config.input_ports["in_port"] = "{my_input_port}";
100  config.output_ports["out_port"] = "{my_output_port}";
101  bb->set("my_input_port", 11);
102 
103  BB_TestNode node("good_one", config);
104  node.executeTick();
105 
106  ASSERT_EQ(bb->get<int>("my_output_port"), 22);
107 }
108 
109 TEST(BlackboardTest, GetInputsFromText)
110 {
111  auto bb = Blackboard::create();
112 
113  NodeConfig config;
114  config.input_ports["in_port"] = "11";
115 
116  BB_TestNode missing_out("missing_output", config);
117  EXPECT_THROW(missing_out.executeTick(), RuntimeError);
118 
119  config.blackboard = bb;
120  config.output_ports["out_port"] = "{=}";
121 
122  BB_TestNode node("good_one", config);
123  node.executeTick();
124 
125  ASSERT_EQ(bb->get<int>("out_port"), 22);
126 }
127 
128 TEST(BlackboardTest, SetOutputFromText)
129 {
130  const char* xml_text = R"(
131 
132  <root BTCPP_format="4" >
133  <BehaviorTree ID="MainTree">
134  <Sequence>
135  <BB_TestNode in_port="11" out_port="{my_port}"/>
136  <Script code="my_port=-43" />
137  </Sequence>
138  </BehaviorTree>
139  </root>
140  )";
141 
142  BehaviorTreeFactory factory;
143  factory.registerNodeType<BB_TestNode>("BB_TestNode");
144 
145  auto bb = Blackboard::create();
146 
147  auto tree = factory.createTreeFromText(xml_text, bb);
148  tree.tickWhileRunning();
149 }
150 
151 TEST(BlackboardTest, WithFactory)
152 {
153  BehaviorTreeFactory factory;
154 
155  factory.registerNodeType<BB_TestNode>("BB_TestNode");
156 
157  const std::string xml_text = R"(
158 
159  <root BTCPP_format="4" >
160  <BehaviorTree ID="MainTree">
161  <Sequence>
162  <BB_TestNode in_port="11"
163  out_port="{my_input_port}"/>
164 
165  <BB_TestNode in_port="{my_input_port}"
166  out_port="{my_input_port}" />
167 
168  <BB_TestNode in_port="{my_input_port}"
169  out_port="{my_output_port}" />
170  </Sequence>
171  </BehaviorTree>
172  </root>)";
173 
174  auto bb = Blackboard::create();
175 
176  auto tree = factory.createTreeFromText(xml_text, bb);
177  NodeStatus status = tree.tickWhileRunning();
178 
179  ASSERT_EQ(status, NodeStatus::SUCCESS);
180  ASSERT_EQ(bb->get<int>("my_input_port"), 44);
181  ASSERT_EQ(bb->get<int>("my_output_port"), 88);
182 }
183 
184 TEST(BlackboardTest, TypoInPortName)
185 {
186  BehaviorTreeFactory factory;
187  factory.registerNodeType<BB_TestNode>("BB_TestNode");
188 
189  const std::string xml_text = R"(
190 
191  <root BTCPP_format="4" >
192  <BehaviorTree ID="MainTree">
193  <BB_TestNode inpuuuut_port="{value}" />
194  </BehaviorTree>
195  </root>)";
196 
197  ASSERT_THROW(auto tree = factory.createTreeFromText(xml_text), RuntimeError);
198 }
199 
200 TEST(BlackboardTest, CheckPortType)
201 {
202  BehaviorTreeFactory factory;
203  factory.registerNodeType<BB_TypedTestNode>("TypedNode");
204 
205  //-----------------------------
206  std::string good_one = R"(
207  <root BTCPP_format="4" >
208  <BehaviorTree ID="MainTree">
209  <Sequence>
210  <TypedNode name = "first" output_int="{matching}" output_string="{whatever}" output="{no_problem}" />
211  <TypedNode name = "second" input_int="{matching}" input="{whatever}" input_string="{no_problem}" />
212  </Sequence>
213  </BehaviorTree>
214  </root>)";
215 
216  auto tree = factory.createTreeFromText(good_one);
217  ASSERT_NE(tree.rootNode(), nullptr);
218  //-----------------------------
219  std::string bad_one = R"(
220  <root BTCPP_format="4" >
221  <BehaviorTree ID="MainTree">
222  <Sequence>
223  <TypedNode name = "first" output_int="{value}" />
224  <TypedNode name = "second" input_string="{value}" />
225  </Sequence>
226  </BehaviorTree>
227  </root>)";
228 
229  ASSERT_THROW(auto tree = factory.createTreeFromText(bad_one), RuntimeError);
230 }
231 
233 {
234 public:
235  RefCountClass(std::shared_ptr<int> value) : sptr_(std::move(value))
236  {
237  std::cout << "Constructor: ref_count " << sptr_.use_count() << std::endl;
238  }
239 
240  RefCountClass(const RefCountClass& from) : sptr_(from.sptr_)
241  {
242  std::cout << "ctor copy: ref_count " << sptr_.use_count() << std::endl;
243  }
244 
246  {
247  sptr_ = (from.sptr_);
248  std::cout << "equal copied: ref_count " << sptr_.use_count() << std::endl;
249  return *this;
250  }
251 
252  virtual ~RefCountClass()
253  {
254  std::cout << ("Destructor") << std::endl;
255  }
256 
257  int refCount() const
258  {
259  return sptr_.use_count();
260  }
261 
262 private:
263  std::shared_ptr<int> sptr_;
264 };
265 
266 TEST(BlackboardTest, MoveVsCopy)
267 {
268  auto blackboard = Blackboard::create();
269 
270  RefCountClass test(std::make_shared<int>());
271 
272  ASSERT_EQ(test.refCount(), 1);
273 
274  std::cout << ("----- before set -----") << std::endl;
275  blackboard->set("testmove", test);
276  std::cout << (" ----- after set -----") << std::endl;
277 
278  ASSERT_EQ(test.refCount(), 2);
279 
280  RefCountClass other(blackboard->get<RefCountClass>("testmove"));
281 
282  ASSERT_EQ(test.refCount(), 3);
283 }
284 
285 TEST(BlackboardTest, CheckTypeSafety)
286 {
287  //TODO check type safety when ports are created.
288  // remember that std::string is considered a type erased type.
289 
291  ASSERT_TRUE(is);
292 
294  ASSERT_TRUE(is);
295 }
296 
297 TEST(BlackboardTest, AnyPtrLocked)
298 {
299  auto blackboard = Blackboard::create();
300  long value = 0;
301  long* test_obj = &value;
302 
303  blackboard->set("testmove", test_obj);
304 
305  auto const timeout = std::chrono::milliseconds(250);
306 
307  // Safe way to access a pointer
308  {
309  std::atomic_llong cycles = 0;
310  auto func = [&]() {
311  auto start = std::chrono::system_clock::now();
312  while((std::chrono::system_clock::now() - start) < timeout)
313  {
314  auto r1 = blackboard->getAnyLocked("testmove");
315  auto value_ptr = (r1.get()->cast<long*>());
316  (*value_ptr)++;
317  cycles++;
318  }
319  };
320 
321  auto t1 = std::thread(func); // other thread
322  func(); // this thread
323  t1.join();
324 
325  // number of increments and cycles is expected to be the same
326  ASSERT_EQ(cycles, value);
327  }
328  //------------------
329  // UNSAFE way to access a pointer
330  {
331  std::atomic_llong cycles = 0;
332  auto func = [&]() {
333  auto start = std::chrono::system_clock::now();
334  while((std::chrono::system_clock::now() - start) < timeout)
335  {
336  auto value_ptr = blackboard->get<long*>("testmove");
337  (*value_ptr)++;
338  cycles++;
339  }
340  };
341 
342  auto t1 = std::thread(func);
343  func();
344  t1.join();
345  // since the operation value_ptr++ is not thread safe, cycle and value will unlikely be the same
346  ASSERT_NE(cycles, value);
347  }
348 }
349 
350 TEST(BlackboardTest, SetStringView)
351 {
352  auto bb = Blackboard::create();
353 
354  constexpr BT::StringView string_view_const = "BehaviorTreeCpp";
355  bb->set("string_view", string_view_const);
356 
357  ASSERT_NO_THROW(bb->set("string_view", string_view_const));
358 }
359 
360 TEST(ParserTest, Issue605_whitespaces)
361 {
362  BT::BehaviorTreeFactory factory;
363 
364  const std::string xml_text = R"(
365  <root BTCPP_format="4" >
366  <BehaviorTree ID="MySubtree">
367  <Script code=" sub_value:=false " />
368  </BehaviorTree>
369 
370  <BehaviorTree ID="MainTree">
371  <Sequence>
372  <Script code=" my_value:=true " />
373  <SubTree ID="MySubtree" sub_value="{my_value} "/>
374  </Sequence>
375  </BehaviorTree>
376  </root> )";
377 
379  auto tree = factory.createTree("MainTree");
380  const auto status = tree.tickWhileRunning();
381 
382  for(auto const& subtree : tree.subtrees)
383  {
384  subtree->blackboard->debugMessage();
385  }
386 
387  ASSERT_EQ(status, BT::NodeStatus::SUCCESS);
388  ASSERT_EQ(false, tree.rootBlackboard()->get<bool>("my_value"));
389 }
390 
392 {
393 public:
394  ComparisonNode(const std::string& name, const BT::NodeConfiguration& config)
395  : BT::ConditionNode(name, config)
396  {}
397 
399  {
400  return { BT::InputPort<int32_t>("first"), BT::InputPort<int32_t>("second"),
401  BT::InputPort<std::string>("operator") };
402  }
403 
404  BT::NodeStatus tick() override
405  {
406  int32_t firstValue = 0;
407  int32_t secondValue = 0;
408  std::string inputOperator;
409  if(!getInput("first", firstValue) || !getInput("second", secondValue) ||
410  !getInput("operator", inputOperator))
411  {
412  throw RuntimeError("can't access input");
413  }
414  if((inputOperator == "==" && firstValue == secondValue) ||
415  (inputOperator == "!=" && firstValue != secondValue) ||
416  (inputOperator == "<=" && firstValue <= secondValue) ||
417  (inputOperator == ">=" && firstValue >= secondValue) ||
418  (inputOperator == "<" && firstValue < secondValue) ||
419  (inputOperator == ">" && firstValue > secondValue))
420  {
422  }
423  // skipping the rest of the implementation
425  }
426 };
427 
428 TEST(BlackboardTest, IssueSetBlackboard)
429 {
430  BT::BehaviorTreeFactory factory;
431 
432  const std::string xml_text = R"(
433  <root BTCPP_format="4" >
434  <BehaviorTree ID="MySubtree">
435  <ComparisonNode first="{value}" second="42" operator="==" />
436  </BehaviorTree>
437 
438  <BehaviorTree ID="MainTree">
439  <Sequence>
440  <SetBlackboard value="42" output_key="value" />
441  <SubTree ID="MySubtree" value="{value} "/>
442  </Sequence>
443  </BehaviorTree>
444  </root> )";
445 
446  factory.registerNodeType<ComparisonNode>("ComparisonNode");
448  auto tree = factory.createTree("MainTree");
449  const auto status = tree.tickWhileRunning();
450 
451  ASSERT_EQ(status, BT::NodeStatus::SUCCESS);
452  ASSERT_EQ(42, tree.rootBlackboard()->get<int>("value"));
453 }
454 
455 struct Point
456 {
457  double x;
458  double y;
459 };
460 
461 TEST(BlackboardTest, SetBlackboard_Issue725)
462 {
463  BT::BehaviorTreeFactory factory;
464 
465  const std::string xml_text = R"(
466  <root BTCPP_format="4">
467  <BehaviorTree ID="MainTree">
468  <SetBlackboard value="{first_point}" output_key="other_point" />
469  </BehaviorTree>
470  </root> )";
471 
472  factory.registerNodeType<DummyNodes::SaySomething>("SaySomething");
474  auto tree = factory.createTree("MainTree");
475  auto& blackboard = tree.subtrees.front()->blackboard;
476 
477  const Point point = { 2, 7 };
478  blackboard->set("first_point", point);
479 
480  const auto status = tree.tickOnce();
481 
482  Point other_point = blackboard->get<Point>("other_point");
483 
484  ASSERT_EQ(status, BT::NodeStatus::SUCCESS);
485  ASSERT_EQ(other_point.x, point.x);
486  ASSERT_EQ(other_point.y, point.y);
487 }
488 
489 TEST(BlackboardTest, NullOutputRemapping)
490 {
491  auto bb = Blackboard::create();
492 
493  NodeConfig config;
494 
495  config.blackboard = bb;
496  config.input_ports["in_port"] = "{my_input_port}";
497  config.output_ports["out_port"] = "";
498  bb->set("my_input_port", 11);
499 
500  BB_TestNode node("good_one", config);
501 
502  // This will throw because setOutput should fail in BB_TestNode::tick()
503  ASSERT_ANY_THROW(node.executeTick());
504 }
505 
506 TEST(BlackboardTest, BlackboardBackup)
507 {
508  BT::BehaviorTreeFactory factory;
509 
510  const std::string xml_text = R"(
511  <root BTCPP_format="4" >
512  <BehaviorTree ID="MySubtree">
513  <Sequence>
514  <Script code=" important_value:= sub_value " />
515  <Script code=" my_value=false " />
516  <SaySomething message="{message}" />
517  </Sequence>
518  </BehaviorTree>
519  <BehaviorTree ID="MainTree">
520  <Sequence>
521  <Script code=" my_value:=true; another_value:='hi' " />
522  <SubTree ID="MySubtree" sub_value="true" message="{another_value}" _autoremap="true" />
523  </Sequence>
524  </BehaviorTree>
525  </root> )";
526 
527  factory.registerNodeType<DummyNodes::SaySomething>("SaySomething");
529  auto tree = factory.createTree("MainTree");
530 
531  // Blackboard Backup
532  const auto bb_backup = BlackboardBackup(tree);
533 
534  std::vector<std::vector<std::string>> expected_keys;
535  for(const auto& sub : tree.subtrees)
536  {
537  std::vector<std::string> keys;
538  for(const auto& str_view : sub->blackboard->getKeys())
539  {
540  keys.push_back(std::string(str_view));
541  }
542  expected_keys.push_back(keys);
543  }
544 
545  auto status = tree.tickWhileRunning();
546 
547  ASSERT_EQ(status, BT::NodeStatus::SUCCESS);
548 
549  // Restore Blackboard
550  ASSERT_EQ(bb_backup.size(), tree.subtrees.size());
551  BlackboardRestore(bb_backup, tree);
552 
553  for(size_t i = 0; i < tree.subtrees.size(); i++)
554  {
555  const auto keys = tree.subtrees[i]->blackboard->getKeys();
556  ASSERT_EQ(expected_keys[i].size(), keys.size());
557  for(size_t a = 0; a < keys.size(); a++)
558  {
559  ASSERT_EQ(expected_keys[i][a], keys[a]);
560  }
561  }
562  status = tree.tickWhileRunning();
563  ASSERT_EQ(status, BT::NodeStatus::SUCCESS);
564 }
565 
566 TEST(BlackboardTest, RootBlackboard)
567 {
568  BT::BehaviorTreeFactory factory;
569 
570  const std::string xml_text = R"(
571  <root BTCPP_format="4" >
572  <BehaviorTree ID="SubA">
573  <Sequence>
574  <SubTree ID="SubB" />
575  <Script code=" @var3:=3 " />
576  </Sequence>
577  </BehaviorTree>
578 
579  <BehaviorTree ID="SubB">
580  <Sequence>
581  <SaySomething message="{@msg}" />
582  <Script code=" @var4:=4 " />
583  </Sequence>
584  </BehaviorTree>
585 
586  <BehaviorTree ID="Sub_Issue823">
587  <BB_TestNode in_port="2" out_port="{@var5}" />
588  </BehaviorTree>
589 
590  <BehaviorTree ID="MainTree">
591  <Sequence>
592  <Script code=" msg:='hello' " />
593  <SubTree ID="SubA" />
594 
595  <Script code="@var5:=0" />
596  <SubTree ID="Sub_Issue823" />
597 
598  <Script code=" var1:=1 " />
599  <Script code=" @var2:=2 " />
600  </Sequence>
601  </BehaviorTree>
602  </root> )";
603 
604  factory.registerNodeType<DummyNodes::SaySomething>("SaySomething");
605  factory.registerNodeType<BB_TestNode>("BB_TestNode");
607  auto tree = factory.createTree("MainTree");
608 
609  auto status = tree.tickWhileRunning();
610  ASSERT_EQ(status, BT::NodeStatus::SUCCESS);
611 
612  ASSERT_EQ(1, tree.rootBlackboard()->get<int>("var1"));
613  ASSERT_EQ(2, tree.rootBlackboard()->get<int>("var2"));
614  ASSERT_EQ(3, tree.rootBlackboard()->get<int>("var3"));
615  ASSERT_EQ(4, tree.rootBlackboard()->get<int>("var4"));
616  ASSERT_EQ(4, tree.rootBlackboard()->get<int>("var5"));
617 }
618 
619 TEST(BlackboardTest, TimestampedInterface)
620 {
621  auto bb = BT::Blackboard::create();
622 
623  // still empty, expected to fail
624  int value;
625  ASSERT_FALSE(bb->getStamped<int>("value"));
626  ASSERT_FALSE(bb->getStamped("value", value));
627 
628  auto nsec_before = std::chrono::steady_clock::now().time_since_epoch().count();
629  bb->set("value", 42);
630  auto result = bb->getStamped<int>("value");
631  auto stamp_opt = bb->getStamped<int>("value", value);
632 
633  ASSERT_EQ(result->value, 42);
634  ASSERT_EQ(result->stamp.seq, 1);
635  ASSERT_GE(result->stamp.time.count(), nsec_before);
636 
637  ASSERT_EQ(value, 42);
638  ASSERT_TRUE(stamp_opt);
639  ASSERT_EQ(stamp_opt->seq, 1);
640  ASSERT_GE(stamp_opt->time.count(), nsec_before);
641 
642  //---------------------------------
643  nsec_before = std::chrono::steady_clock::now().time_since_epoch().count();
644  bb->set("value", 69);
645  result = bb->getStamped<int>("value");
646  stamp_opt = bb->getStamped<int>("value", value);
647 
648  ASSERT_EQ(result->value, 69);
649  ASSERT_EQ(result->stamp.seq, 2);
650  ASSERT_GE(result->stamp.time.count(), nsec_before);
651 
652  ASSERT_EQ(value, 69);
653  ASSERT_TRUE(stamp_opt);
654  ASSERT_EQ(stamp_opt->seq, 2);
655  ASSERT_GE(stamp_opt->time.count(), nsec_before);
656 }
cx::size
constexpr auto size(const C &c) -> decltype(c.size())
Definition: wildcards.hpp:636
BT
Definition: ex01_wrap_legacy.cpp:29
ComparisonNode
Definition: gtest_blackboard.cpp:391
ComparisonNode::tick
BT::NodeStatus tick() override
Method to be implemented by the user.
Definition: gtest_blackboard.cpp:404
BT::BlackboardRestore
void BlackboardRestore(const std::vector< Blackboard::Ptr > &backup, BT::Tree &tree)
BlackboardRestore uses Blackboard::cloneInto to restore all the blackboards of the tree.
Definition: bt_factory.cpp:679
BT::ConditionNode
Definition: condition_node.h:21
BB_TestNode::BB_TestNode
BB_TestNode(const std::string &name, const NodeConfig &config)
Definition: gtest_blackboard.cpp:24
BT::BehaviorTreeFactory::createTree
Tree createTree(const std::string &tree_name, Blackboard::Ptr blackboard=Blackboard::create())
Definition: bt_factory.cpp:432
ComparisonNode::ComparisonNode
ComparisonNode(const std::string &name, const BT::NodeConfiguration &config)
Definition: gtest_blackboard.cpp:394
BB_TestNode
Definition: gtest_blackboard.cpp:21
RefCountClass
Definition: gtest_blackboard.cpp:232
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:470
RefCountClass::sptr_
std::shared_ptr< int > sptr_
Definition: gtest_blackboard.cpp:263
BT::NodeConfig::input_ports
PortsRemapping input_ports
Definition: tree_node.h:83
RefCountClass::RefCountClass
RefCountClass(const RefCountClass &from)
Definition: gtest_blackboard.cpp:240
bt_factory.h
TEST
TEST(BlackboardTest, GetInputsFromBlackboard)
Definition: gtest_blackboard.cpp:74
magic_enum::detail::value
constexpr E value(std::size_t i) noexcept
Definition: magic_enum.hpp:664
BT::SyncActionNode::executeTick
virtual NodeStatus executeTick() override
throws if the derived class return RUNNING.
Definition: action_node.cpp:56
BB_TypedTestNode::providedPorts
static PortsList providedPorts()
Definition: gtest_blackboard.cpp:62
BT::Tree::tickWhileRunning
NodeStatus tickWhileRunning(std::chrono::milliseconds sleep_time=std::chrono::milliseconds(10))
Definition: bt_factory.cpp:609
BT::NodeConfig::blackboard
Blackboard::Ptr blackboard
Definition: tree_node.h:79
BT::PortsList
std::unordered_map< std::string, PortInfo > PortsList
Definition: basic_types.h:585
BT::NodeStatus::FAILURE
@ FAILURE
BT::BehaviorTreeFactory::registerNodeType
void registerNodeType(const std::string &ID, const PortsList &ports, ExtraArgs... args)
Definition: bt_factory.h:322
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:395
Point
Definition: gtest_blackboard.cpp:455
BT::RuntimeError
Definition: exceptions.h:58
RefCountClass::RefCountClass
RefCountClass(std::shared_ptr< int > value)
Definition: gtest_blackboard.cpp:235
DummyNodes::SaySomething
Definition: dummy_nodes.h:47
BT::LockedPtr
The LockedPtr class is used to share a pointer to an object and a mutex that protects the read/write ...
Definition: locked_reference.hpp:16
BB_TypedTestNode::tick
NodeStatus tick()
Method to be implemented by the user.
Definition: gtest_blackboard.cpp:57
BT::BehaviorTreeFactory
The BehaviorTreeFactory is used to create instances of a TreeNode at run-time.
Definition: bt_factory.h:205
BT::Blackboard::create
static Blackboard::Ptr create(Blackboard::Ptr parent={})
Definition: blackboard.h:63
RefCountClass::refCount
int refCount() const
Definition: gtest_blackboard.cpp:257
BT::NodeStatus::SUCCESS
@ SUCCESS
RefCountClass::operator=
RefCountClass & operator=(const RefCountClass &from)
Definition: gtest_blackboard.cpp:245
BT::Tree::subtrees
std::vector< Subtree::Ptr > subtrees
Definition: bt_factory.h:104
BT::BlackboardBackup
std::vector< Blackboard::Ptr > BlackboardBackup(const BT::Tree &tree)
BlackboardBackup uses Blackboard::cloneInto to backup all the blackboards of the tree.
Definition: bt_factory.cpp:688
RefCountClass::~RefCountClass
virtual ~RefCountClass()
Definition: gtest_blackboard.cpp:252
BT::OutputPort
std::pair< std::string, PortInfo > OutputPort(StringView name, StringView description={})
Definition: basic_types.h:482
std
Definition: std.hpp:30
BT::BehaviorTreeFactory::registerBehaviorTreeFromText
void registerBehaviorTreeFromText(const std::string &xml_text)
Definition: bt_factory.cpp:277
BT::NodeConfig::output_ports
PortsRemapping output_ports
Definition: tree_node.h:85
BB_TypedTestNode
Definition: gtest_blackboard.cpp:50
Point::y
double y
Definition: gtest_blackboard.cpp:458
Point::x
double x
Definition: gtest_blackboard.cpp:457
BT::NodeConfig
Definition: tree_node.h:73
blackboard.h
BB_TestNode::tick
NodeStatus tick()
Method to be implemented by the user.
Definition: gtest_blackboard.cpp:28
xml_text
static const char * xml_text
Definition: ex01_wrap_legacy.cpp:52
BB_TypedTestNode::BB_TypedTestNode
BB_TypedTestNode(const std::string &name, const NodeConfig &config)
Definition: gtest_blackboard.cpp:53
BT::SyncActionNode
The SyncActionNode is an ActionNode that explicitly prevents the status RUNNING and doesn't require a...
Definition: action_node.h:52
ComparisonNode::providedPorts
static BT::PortsList providedPorts()
Definition: gtest_blackboard.cpp:398
BT::NodeStatus
NodeStatus
Definition: basic_types.h:33
BB_TestNode::providedPorts
static PortsList providedPorts()
Definition: gtest_blackboard.cpp:44


behaviortree_cpp_v4
Author(s): Davide Faconti
autogenerated on Fri Jun 28 2024 02:20:07