gtest_parallel.cpp
Go to the documentation of this file.
1 /* Copyright (C) 2015-2017 Michele Colledanchise - All Rights Reserved
2 * Copyright (C) 2018-2023 Davide Faconti - All Rights Reserved
3 *
4 * Permission is hereby granted, free of charge, to any person obtaining a copy of this software and associated documentation files (the "Software"),
5 * to deal in the Software without restriction, including without limitation the rights to use, copy, modify, merge, publish, distribute, sublicense,
6 * 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:
7 * The above copyright notice and this permission notice shall be included in all copies or substantial portions of the Software.
8 *
9 * THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY,
10 * 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,
11 * 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.
12 */
13 
14 #include <gtest/gtest.h>
15 #include "action_test_node.h"
17 #include "condition_test_node.h"
19 #include "test_helper.hpp"
20 
21 using BT::NodeStatus;
22 using std::chrono::milliseconds;
23 
24 struct SimpleParallelTest : testing::Test
25 {
29 
32 
34  : root("root_parallel")
35  , action_1("action_1", milliseconds(100))
36  , condition_1("condition_1")
37  , action_2("action_2", milliseconds(300))
38  , condition_2("condition_2")
39  {
44  }
46  {}
47 };
48 
49 struct ComplexParallelTest : testing::Test
50 {
54 
57 
60 
63 
65  : parallel_root("root")
66  , parallel_left("par1")
67  , parallel_right("par2")
68  , action_L1("action_1", milliseconds(100))
69  , condition_L1("condition_1")
70  , action_L2("action_2", milliseconds(200))
71  , condition_L2("condition_2")
72  , action_R("action_3", milliseconds(400))
73  , condition_R("condition_3")
74  {
76  {
81  }
83  {
86  }
90  }
92  {}
93 };
94 
95 /****************TESTS START HERE***************************/
96 
97 TEST_F(SimpleParallelTest, ConditionsTrue)
98 {
99  BT::NodeStatus state = root.executeTick();
100 
101  ASSERT_EQ(NodeStatus::SUCCESS, condition_1.status());
102  ASSERT_EQ(NodeStatus::SUCCESS, condition_2.status());
103  ASSERT_EQ(NodeStatus::RUNNING, action_1.status());
104  ASSERT_EQ(NodeStatus::RUNNING, action_2.status());
105  ASSERT_EQ(NodeStatus::RUNNING, state);
106 
107  std::this_thread::sleep_for(milliseconds(200));
108  state = root.executeTick();
109 
110  ASSERT_EQ(NodeStatus::SUCCESS, condition_1.status());
111  ASSERT_EQ(NodeStatus::SUCCESS, condition_2.status());
112  ASSERT_EQ(NodeStatus::SUCCESS, action_1.status());
113  ASSERT_EQ(NodeStatus::RUNNING, action_2.status());
114  ASSERT_EQ(NodeStatus::RUNNING, state);
115 
116  std::this_thread::sleep_for(milliseconds(200));
117  state = root.executeTick();
118 
119  ASSERT_EQ(NodeStatus::IDLE, condition_1.status());
120  ASSERT_EQ(NodeStatus::IDLE, condition_2.status());
121  ASSERT_EQ(NodeStatus::IDLE, action_1.status());
122  ASSERT_EQ(NodeStatus::IDLE, action_2.status());
123  ASSERT_EQ(NodeStatus::SUCCESS, state);
124 }
125 
127 {
128  root.setSuccessThreshold(3);
129  action_1.setTime(milliseconds(100));
130  action_2.setTime(milliseconds(500)); // this takes a lot of time
131 
132  BT::NodeStatus state = root.executeTick();
133  // first tick, zero wait
134  ASSERT_EQ(NodeStatus::SUCCESS, condition_1.status());
135  ASSERT_EQ(NodeStatus::SUCCESS, condition_2.status());
136  ASSERT_EQ(NodeStatus::RUNNING, action_1.status());
137  ASSERT_EQ(NodeStatus::RUNNING, action_2.status());
138  ASSERT_EQ(NodeStatus::RUNNING, state);
139 
140  std::this_thread::sleep_for(milliseconds(150));
141  state = root.executeTick();
142  // second tick: action1 should be completed, but not action2
143  // nevertheless it is sufficient because threshold is 3
144  ASSERT_EQ(NodeStatus::IDLE, condition_1.status());
145  ASSERT_EQ(NodeStatus::IDLE, condition_2.status());
146  ASSERT_EQ(NodeStatus::IDLE, action_1.status());
147  ASSERT_EQ(NodeStatus::IDLE, action_2.status());
148  ASSERT_EQ(NodeStatus::SUCCESS, state);
149 }
150 
151 TEST_F(SimpleParallelTest, Threshold_neg2)
152 {
153  root.setSuccessThreshold(-2);
154  action_1.setTime(milliseconds(100));
155  action_2.setTime(milliseconds(500)); // this takes a lot of time
156 
157  BT::NodeStatus state = root.executeTick();
158  // first tick, zero wait
159  ASSERT_EQ(NodeStatus::SUCCESS, condition_1.status());
160  ASSERT_EQ(NodeStatus::SUCCESS, condition_2.status());
161  ASSERT_EQ(NodeStatus::RUNNING, action_1.status());
162  ASSERT_EQ(NodeStatus::RUNNING, action_2.status());
163  ASSERT_EQ(NodeStatus::RUNNING, state);
164 
165  std::this_thread::sleep_for(milliseconds(150));
166  state = root.executeTick();
167  // second tick: action1 should be completed, but not action2
168  // nevertheless it is sufficient because threshold is 3
169  ASSERT_EQ(NodeStatus::IDLE, condition_1.status());
170  ASSERT_EQ(NodeStatus::IDLE, condition_2.status());
171  ASSERT_EQ(NodeStatus::IDLE, action_1.status());
172  ASSERT_EQ(NodeStatus::IDLE, action_2.status());
173  ASSERT_EQ(NodeStatus::SUCCESS, state);
174 }
175 
176 TEST_F(SimpleParallelTest, Threshold_neg1)
177 {
178  root.setSuccessThreshold(-1);
179  action_1.setTime(milliseconds(100));
180  action_2.setTime(milliseconds(500)); // this takes a lot of time
181 
182  BT::NodeStatus state = root.executeTick();
183  // first tick, zero wait
184  ASSERT_EQ(NodeStatus::SUCCESS, condition_1.status());
185  ASSERT_EQ(NodeStatus::SUCCESS, condition_2.status());
186  ASSERT_EQ(NodeStatus::RUNNING, action_1.status());
187  ASSERT_EQ(NodeStatus::RUNNING, action_2.status());
188  ASSERT_EQ(NodeStatus::RUNNING, state);
189 
190  std::this_thread::sleep_for(milliseconds(150));
191  state = root.executeTick();
192  // second tick: action1 should be completed, but not action2
193  ASSERT_EQ(NodeStatus::SUCCESS, condition_1.status());
194  ASSERT_EQ(NodeStatus::SUCCESS, condition_2.status());
195  ASSERT_EQ(NodeStatus::SUCCESS, action_1.status());
196  ASSERT_EQ(NodeStatus::RUNNING, action_2.status());
197  ASSERT_EQ(NodeStatus::RUNNING, state);
198 
199  std::this_thread::sleep_for(milliseconds(650));
200  state = root.executeTick();
201  // third tick: all actions completed
202  ASSERT_EQ(NodeStatus::IDLE, condition_1.status());
203  ASSERT_EQ(NodeStatus::IDLE, condition_2.status());
204  ASSERT_EQ(NodeStatus::IDLE, action_1.status());
205  ASSERT_EQ(NodeStatus::IDLE, action_2.status());
206  ASSERT_EQ(NodeStatus::SUCCESS, state);
207 }
208 
209 TEST_F(SimpleParallelTest, Threshold_thresholdFneg1)
210 {
211  root.setSuccessThreshold(1);
212  root.setFailureThreshold(-1);
213  action_1.setTime(milliseconds(100));
214  action_1.setExpectedResult(NodeStatus::FAILURE);
215  condition_1.setExpectedResult(NodeStatus::FAILURE);
216  action_2.setTime(milliseconds(200));
217  condition_2.setExpectedResult(NodeStatus::FAILURE);
218  action_2.setExpectedResult(NodeStatus::FAILURE);
219 
220  BT::NodeStatus state = root.executeTick();
221  ASSERT_EQ(NodeStatus::RUNNING, state);
222 
223  std::this_thread::sleep_for(milliseconds(250));
224  state = root.executeTick();
225  ASSERT_EQ(NodeStatus::FAILURE, state);
226 }
227 
229 {
230  root.setSuccessThreshold(2);
231  BT::NodeStatus state = root.executeTick();
232 
233  ASSERT_EQ(NodeStatus::IDLE, condition_1.status());
234  ASSERT_EQ(NodeStatus::IDLE, condition_2.status());
235  ASSERT_EQ(NodeStatus::IDLE, action_1.status());
236  ASSERT_EQ(NodeStatus::IDLE, action_2.status());
237  ASSERT_EQ(NodeStatus::SUCCESS, state);
238 }
239 
240 TEST_F(ComplexParallelTest, ConditionsTrue)
241 {
242  BT::NodeStatus state = parallel_root.executeTick();
243 
244  ASSERT_EQ(NodeStatus::RUNNING, parallel_left.status());
245  ASSERT_EQ(NodeStatus::SUCCESS, condition_L1.status());
246  ASSERT_EQ(NodeStatus::SUCCESS, condition_L2.status());
247  ASSERT_EQ(NodeStatus::RUNNING, action_L1.status());
248  ASSERT_EQ(NodeStatus::RUNNING, action_L2.status());
249 
250  ASSERT_EQ(NodeStatus::SUCCESS, parallel_right.status());
251  ASSERT_EQ(NodeStatus::IDLE, condition_R.status());
252  ASSERT_EQ(NodeStatus::IDLE, action_R.status());
253 
254  ASSERT_EQ(NodeStatus::RUNNING, state);
255  //----------------------------------------
256  std::this_thread::sleep_for(milliseconds(200));
257  state = parallel_root.executeTick();
258 
259  ASSERT_EQ(NodeStatus::IDLE, parallel_left.status());
260  ASSERT_EQ(NodeStatus::IDLE, condition_L1.status());
261  ASSERT_EQ(NodeStatus::IDLE, condition_L2.status());
262  ASSERT_EQ(NodeStatus::IDLE, action_L1.status());
263  ASSERT_EQ(NodeStatus::IDLE, action_L2.status());
264 
265  ASSERT_EQ(NodeStatus::IDLE, parallel_right.status());
266  ASSERT_EQ(NodeStatus::IDLE, condition_R.status());
267  ASSERT_EQ(NodeStatus::IDLE, action_R.status());
268 
269  ASSERT_EQ(NodeStatus::SUCCESS, state);
270 }
271 
272 TEST_F(ComplexParallelTest, ConditionsLeftFalse)
273 {
274  parallel_left.setFailureThreshold(3);
275  parallel_left.setSuccessThreshold(3);
276  condition_L1.setExpectedResult(NodeStatus::FAILURE);
277  condition_L2.setExpectedResult(NodeStatus::FAILURE);
278  BT::NodeStatus state = parallel_root.executeTick();
279 
280  // It fails because Parallel Left it will never succeed (two already fail)
281  // even though threshold_failure == 3
282 
283  ASSERT_EQ(NodeStatus::IDLE, parallel_left.status());
284  ASSERT_EQ(NodeStatus::IDLE, condition_L1.status());
285  ASSERT_EQ(NodeStatus::IDLE, condition_L2.status());
286  ASSERT_EQ(NodeStatus::IDLE, action_L1.status());
287  ASSERT_EQ(NodeStatus::IDLE, action_L2.status());
288 
289  ASSERT_EQ(NodeStatus::IDLE, parallel_right.status());
290  ASSERT_EQ(NodeStatus::IDLE, condition_R.status());
291  ASSERT_EQ(NodeStatus::IDLE, action_R.status());
292 
293  ASSERT_EQ(NodeStatus::FAILURE, state);
294 }
295 
296 TEST_F(ComplexParallelTest, ConditionRightFalse)
297 {
298  condition_R.setExpectedResult(NodeStatus::FAILURE);
299  BT::NodeStatus state = parallel_root.executeTick();
300 
301  // It fails because threshold_failure is 1 for parallel right and
302  // condition_R fails
303 
304  ASSERT_EQ(NodeStatus::IDLE, parallel_left.status());
305  ASSERT_EQ(NodeStatus::IDLE, condition_L1.status());
306  ASSERT_EQ(NodeStatus::IDLE, condition_L2.status());
307  ASSERT_EQ(NodeStatus::IDLE, action_L1.status());
308  ASSERT_EQ(NodeStatus::IDLE, action_L2.status());
309 
310  ASSERT_EQ(NodeStatus::IDLE, parallel_right.status());
311  ASSERT_EQ(NodeStatus::IDLE, condition_R.status());
312  ASSERT_EQ(NodeStatus::IDLE, action_R.status());
313 
314  ASSERT_EQ(NodeStatus::FAILURE, state);
315 }
316 
317 TEST_F(ComplexParallelTest, ConditionRightFalse_thresholdF_2)
318 {
319  parallel_right.setFailureThreshold(2);
320  condition_R.setExpectedResult(NodeStatus::FAILURE);
321  BT::NodeStatus state = parallel_root.executeTick();
322 
323  // All the actions are running
324 
325  ASSERT_EQ(NodeStatus::RUNNING, parallel_left.status());
326  ASSERT_EQ(NodeStatus::SUCCESS, condition_L1.status());
327  ASSERT_EQ(NodeStatus::SUCCESS, condition_L2.status());
328  ASSERT_EQ(NodeStatus::RUNNING, action_L1.status());
329  ASSERT_EQ(NodeStatus::RUNNING, action_L2.status());
330 
331  ASSERT_EQ(NodeStatus::RUNNING, parallel_right.status());
332  ASSERT_EQ(NodeStatus::FAILURE, condition_R.status());
333  ASSERT_EQ(NodeStatus::RUNNING, action_R.status());
334 
335  ASSERT_EQ(NodeStatus::RUNNING, state);
336 
337  //----------------------------------------
338  std::this_thread::sleep_for(milliseconds(500));
339  state = parallel_root.executeTick();
340 
341  ASSERT_EQ(NodeStatus::IDLE, parallel_left.status());
342  ASSERT_EQ(NodeStatus::IDLE, condition_L1.status());
343  ASSERT_EQ(NodeStatus::IDLE, condition_L2.status());
344  ASSERT_EQ(NodeStatus::IDLE, action_L1.status());
345  ASSERT_EQ(NodeStatus::IDLE, action_L2.status());
346 
347  ASSERT_EQ(NodeStatus::IDLE, parallel_right.status());
348  ASSERT_EQ(NodeStatus::IDLE, condition_R.status());
349  ASSERT_EQ(NodeStatus::IDLE, action_R.status());
350 
351  ASSERT_EQ(NodeStatus::SUCCESS, state);
352 }
353 
354 TEST_F(ComplexParallelTest, ConditionRightFalseAction1Done)
355 {
356  condition_R.setExpectedResult(NodeStatus::FAILURE);
357 
358  parallel_right.setFailureThreshold(2);
359  parallel_left.setSuccessThreshold(4);
360 
361  BT::NodeStatus state = parallel_root.executeTick();
362  std::this_thread::sleep_for(milliseconds(300));
363 
364  // parallel_1 hasn't realize (yet) that action_1 has succeeded
365  ASSERT_EQ(NodeStatus::RUNNING, parallel_left.status());
366  ASSERT_EQ(NodeStatus::SUCCESS, condition_L1.status());
367  ASSERT_EQ(NodeStatus::SUCCESS, condition_L2.status());
368  ASSERT_EQ(NodeStatus::SUCCESS, action_L1.status());
369  ASSERT_EQ(NodeStatus::SUCCESS, action_L2.status());
370 
371  ASSERT_EQ(NodeStatus::RUNNING, parallel_right.status());
372 
373  //------------------------
374  state = parallel_root.executeTick();
375 
376  ASSERT_EQ(NodeStatus::SUCCESS, parallel_left.status());
377  ASSERT_EQ(NodeStatus::IDLE, condition_L1.status());
378  ASSERT_EQ(NodeStatus::IDLE, condition_L2.status());
379  ASSERT_EQ(NodeStatus::IDLE, action_L1.status());
380  ASSERT_EQ(NodeStatus::IDLE, action_L2.status());
381 
382  ASSERT_EQ(NodeStatus::RUNNING, parallel_right.status());
383  ASSERT_EQ(NodeStatus::RUNNING, action_R.status());
384 
385  ASSERT_EQ(NodeStatus::RUNNING, state);
386 
387  //----------------------------------
388  std::this_thread::sleep_for(milliseconds(300));
389  state = parallel_root.executeTick();
390 
391  ASSERT_EQ(NodeStatus::IDLE, parallel_left.status());
392  ASSERT_EQ(NodeStatus::IDLE, action_L1.status());
393 
394  ASSERT_EQ(NodeStatus::IDLE, parallel_right.status());
395  ASSERT_EQ(NodeStatus::IDLE, action_R.status());
396 
397  ASSERT_EQ(NodeStatus::SUCCESS, state);
398 }
399 
400 TEST(Parallel, FailingParallel)
401 {
402  static const char* xml_text = R"(
403 <root BTCPP_format="4">
404  <BehaviorTree ID="MainTree">
405  <Parallel name="parallel" success_count="1" failure_count="3">
406  <GoodTest name="first"/>
407  <BadTest name="second"/>
408  <SlowTest name="third"/>
409  </Parallel>
410  </BehaviorTree>
411 </root> )";
412  using namespace BT;
413 
414  BehaviorTreeFactory factory;
415 
416  BT::TestNodeConfig good_config;
417  good_config.async_delay = std::chrono::milliseconds(200);
418  good_config.return_status = NodeStatus::SUCCESS;
419  factory.registerNodeType<BT::TestNode>("GoodTest", good_config);
420 
421  BT::TestNodeConfig bad_config;
422  bad_config.async_delay = std::chrono::milliseconds(100);
423  bad_config.return_status = NodeStatus::FAILURE;
424  factory.registerNodeType<BT::TestNode>("BadTest", bad_config);
425 
426  BT::TestNodeConfig slow_config;
427  slow_config.async_delay = std::chrono::milliseconds(300);
428  slow_config.return_status = NodeStatus::SUCCESS;
429  factory.registerNodeType<BT::TestNode>("SlowTest", slow_config);
430 
431  auto tree = factory.createTreeFromText(xml_text);
432  BT::TreeObserver observer(tree);
433 
434  auto state = tree.tickWhileRunning();
435  // since at least one succeeded.
436  ASSERT_EQ(NodeStatus::SUCCESS, state);
437  ASSERT_EQ(1, observer.getStatistics("first").success_count);
438  ASSERT_EQ(1, observer.getStatistics("second").failure_count);
439  ASSERT_EQ(0, observer.getStatistics("third").failure_count);
440 }
441 
442 TEST(Parallel, ParallelAll)
443 {
444  using namespace BT;
445 
446  BehaviorTreeFactory factory;
447 
448  BT::TestNodeConfig good_config;
449  good_config.async_delay = std::chrono::milliseconds(300);
450  good_config.return_status = NodeStatus::SUCCESS;
451  factory.registerNodeType<BT::TestNode>("GoodTest", good_config);
452 
453  BT::TestNodeConfig bad_config;
454  bad_config.async_delay = std::chrono::milliseconds(100);
455  bad_config.return_status = NodeStatus::FAILURE;
456  factory.registerNodeType<BT::TestNode>("BadTest", bad_config);
457 
458  {
459  const char* xml_text = R"(
460 <root BTCPP_format="4">
461  <BehaviorTree ID="MainTree">
462  <ParallelAll max_failures="1">
463  <BadTest name="first"/>
464  <GoodTest name="second"/>
465  <GoodTest name="third"/>
466  </ParallelAll>
467  </BehaviorTree>
468 </root> )";
469  auto tree = factory.createTreeFromText(xml_text);
470  BT::TreeObserver observer(tree);
471 
472  auto state = tree.tickWhileRunning();
473  ASSERT_EQ(NodeStatus::FAILURE, state);
474  ASSERT_EQ(1, observer.getStatistics("first").failure_count);
475  ASSERT_EQ(1, observer.getStatistics("second").success_count);
476  ASSERT_EQ(1, observer.getStatistics("third").success_count);
477  }
478 
479  {
480  const char* xml_text = R"(
481 <root BTCPP_format="4">
482  <BehaviorTree ID="MainTree">
483  <ParallelAll max_failures="2">
484  <BadTest name="first"/>
485  <GoodTest name="second"/>
486  <GoodTest name="third"/>
487  </ParallelAll>
488  </BehaviorTree>
489 </root> )";
490  auto tree = factory.createTreeFromText(xml_text);
491  BT::TreeObserver observer(tree);
492 
493  auto state = tree.tickWhileRunning();
494  ASSERT_EQ(NodeStatus::SUCCESS, state);
495  ASSERT_EQ(1, observer.getStatistics("first").failure_count);
496  ASSERT_EQ(1, observer.getStatistics("second").success_count);
497  ASSERT_EQ(1, observer.getStatistics("third").success_count);
498  }
499 }
500 
501 TEST(Parallel, Issue593)
502 {
503  static const char* xml_text = R"(
504 <root BTCPP_format="4">
505  <BehaviorTree ID="TestTree">
506  <Sequence>
507  <Script code="test := true"/>
508  <Parallel failure_count="1" success_count="-1">
509  <TestA _skipIf="test == true"/>
510  <Sleep msec="100"/>
511  </Parallel>
512  </Sequence>
513  </BehaviorTree>
514 </root>
515 )";
516  using namespace BT;
517 
518  BehaviorTreeFactory factory;
519  std::array<int, 1> counters;
520  RegisterTestTick(factory, "Test", counters);
521 
522  auto tree = factory.createTreeFromText(xml_text);
523  tree.tickWhileRunning();
524 
525  ASSERT_EQ(0, counters[0]);
526 }
527 
528 TEST(Parallel, PauseWithRetry)
529 {
530  static const char* xml_text = R"(
531 <root BTCPP_format="4">
532  <BehaviorTree ID="TestTree">
533  <Parallel>
534  <Sequence>
535  <Sleep msec="150"/>
536  <Script code="paused := false"/>
537  <Sleep msec="150"/>
538  </Sequence>
539 
540  <Sequence>
541  <Script code="paused := true; done := false"/>
542  <RetryUntilSuccessful _while="paused" num_attempts="-1" _onHalted="done = true">
543  <AlwaysFailure/>
544  </RetryUntilSuccessful>
545  </Sequence>
546  </Parallel>
547  </BehaviorTree>
548 </root>
549 )";
550  using namespace BT;
551 
552  BehaviorTreeFactory factory;
553 
554  auto tree = factory.createTreeFromText(xml_text);
555  auto t1 = std::chrono::system_clock::now();
556  std::chrono::system_clock::time_point done_time;
557  bool done_detected = false;
558 
559  auto status = tree.tickExactlyOnce();
560  auto toMsec = [](const auto& t) {
561  return std::chrono::duration_cast<std::chrono::milliseconds>(t).count();
562  };
563 
564  while(!isStatusCompleted(status))
565  {
566  std::this_thread::sleep_for(std::chrono::milliseconds(1));
567 
568  if(!done_detected)
569  {
570  if(tree.subtrees.front()->blackboard->get<bool>("done"))
571  {
572  done_detected = true;
573  done_time = std::chrono::system_clock::now();
574  std::cout << "detected\n";
575  }
576  }
577  status = tree.tickExactlyOnce();
578  }
579  auto t2 = std::chrono::system_clock::now();
580 
581  ASSERT_EQ(NodeStatus::SUCCESS, status);
582 
583  // tolerate an error in time measurement within this margin
584 #ifdef WIN32
585  const int margin_msec = 40;
586 #else
587  const int margin_msec = 10;
588 #endif
589 
590  // the second branch with the RetryUntilSuccessful should take about 150 ms
591  ASSERT_LE(toMsec(done_time - t1) - 150, margin_msec);
592  // the whole process should take about 300 milliseconds
593  ASSERT_LE(toMsec(t2 - t1) - 300, margin_msec * 2);
594 }
BT
Definition: ex01_wrap_legacy.cpp:29
BT::TestNodeConfig::async_delay
std::chrono::milliseconds async_delay
if async_delay > 0, this action become asynchronous and wait this amount of time
Definition: test_node.h:38
SimpleParallelTest::SimpleParallelTest
SimpleParallelTest()
Definition: gtest_parallel.cpp:33
ComplexParallelTest
Definition: gtest_parallel.cpp:49
ComplexParallelTest::action_L2
BT::AsyncActionTest action_L2
Definition: gtest_parallel.cpp:58
SimpleParallelTest::condition_1
BT::ConditionTestNode condition_1
Definition: gtest_parallel.cpp:28
SimpleParallelTest::action_2
BT::AsyncActionTest action_2
Definition: gtest_parallel.cpp:30
BT::TreeObserver::getStatistics
const NodeStatistics & getStatistics(const std::string &path) const
Definition: bt_observer.cpp:80
RegisterTestTick
void RegisterTestTick(BT::BehaviorTreeFactory &factory, const std::string &name_prefix, std::array< int, N > &tick_counters)
Definition: test_helper.hpp:15
ComplexParallelTest::parallel_left
BT::ParallelNode parallel_left
Definition: gtest_parallel.cpp:52
BT::ParallelNode
The ParallelNode execute all its children concurrently, but not in separate threads!
Definition: parallel_node.h:40
bt_observer.h
ComplexParallelTest::condition_L2
BT::ConditionTestNode condition_L2
Definition: gtest_parallel.cpp:59
ComplexParallelTest::action_L1
BT::AsyncActionTest action_L1
Definition: gtest_parallel.cpp:55
ComplexParallelTest::ComplexParallelTest
ComplexParallelTest()
Definition: gtest_parallel.cpp:64
bt_factory.h
ComplexParallelTest::condition_L1
BT::ConditionTestNode condition_L1
Definition: gtest_parallel.cpp:56
BT::AsyncActionTest
Definition: action_test_node.h:32
ComplexParallelTest::parallel_root
BT::ParallelNode parallel_root
Definition: gtest_parallel.cpp:51
TEST_F
TEST_F(SimpleParallelTest, ConditionsTrue)
Definition: gtest_parallel.cpp:97
ComplexParallelTest::action_R
BT::AsyncActionTest action_R
Definition: gtest_parallel.cpp:61
test_helper.hpp
BT::Tree::tickWhileRunning
NodeStatus tickWhileRunning(std::chrono::milliseconds sleep_time=std::chrono::milliseconds(10))
Definition: bt_factory.cpp:609
BT::TestNodeConfig
Definition: test_node.h:23
condition_test_node.h
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
BT::TreeObserver::NodeStatistics::failure_count
unsigned failure_count
Definition: bt_observer.h:40
BT::TestNodeConfig::return_status
NodeStatus return_status
status to return when the action is completed.
Definition: test_node.h:26
SimpleParallelTest
Definition: gtest_parallel.cpp:24
SimpleParallelTest::condition_2
BT::ConditionTestNode condition_2
Definition: gtest_parallel.cpp:31
ComplexParallelTest::parallel_right
BT::ParallelNode parallel_right
Definition: gtest_parallel.cpp:53
ComplexParallelTest::~ComplexParallelTest
~ComplexParallelTest() override
Definition: gtest_parallel.cpp:91
BT::BehaviorTreeFactory
The BehaviorTreeFactory is used to create instances of a TreeNode at run-time.
Definition: bt_factory.h:205
BT::TreeObserver
The TreeObserver is used to collect statistics about which nodes are executed and their returned stat...
Definition: bt_observer.h:17
BT::NodeStatus::SUCCESS
@ SUCCESS
BT::TreeObserver::NodeStatistics::success_count
unsigned success_count
Definition: bt_observer.h:38
BT::TestNode
The TestNode is a Node that can be configure to:
Definition: test_node.h:64
BT::isStatusCompleted
bool isStatusCompleted(const NodeStatus &status)
Definition: basic_types.h:47
action_test_node.h
ComplexParallelTest::condition_R
BT::ConditionTestNode condition_R
Definition: gtest_parallel.cpp:62
SimpleParallelTest::root
BT::ParallelNode root
Definition: gtest_parallel.cpp:26
BT::ConditionTestNode
Definition: condition_test_node.h:8
BT::ParallelNode::setSuccessThreshold
void setSuccessThreshold(int threshold)
Definition: parallel_node.cpp:171
BT::ControlNode::addChild
void addChild(TreeNode *child)
The method used to add nodes to the children vector.
Definition: control_node.cpp:22
xml_text
static const char * xml_text
Definition: ex01_wrap_legacy.cpp:52
BT::NodeStatus
NodeStatus
Definition: basic_types.h:33
SimpleParallelTest::~SimpleParallelTest
~SimpleParallelTest() override
Definition: gtest_parallel.cpp:45
TEST
TEST(Parallel, FailingParallel)
Definition: gtest_parallel.cpp:400
SimpleParallelTest::action_1
BT::AsyncActionTest action_1
Definition: gtest_parallel.cpp:27


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