@@ -395,15 +395,15 @@ TEST_F(ComplexParallelTest, ConditionRightFalseAction1Done)
395
395
ASSERT_EQ (NodeStatus::SUCCESS, state);
396
396
}
397
397
398
- TEST (FailingParallel , FailingParallel)
398
+ TEST (Parallel , FailingParallel)
399
399
{
400
400
static const char * xml_text = R"(
401
401
<root BTCPP_format="4">
402
402
<BehaviorTree ID="MainTree">
403
403
<Parallel name="parallel" success_count="1" failure_count="3">
404
404
<GoodTest name="first"/>
405
405
<BadTest name="second"/>
406
- <GoodTest name="third"/>
406
+ <SlowTest name="third"/>
407
407
</Parallel>
408
408
</BehaviorTree>
409
409
</root> )" ;
@@ -412,7 +412,7 @@ TEST(FailingParallel, FailingParallel)
412
412
BehaviorTreeFactory factory;
413
413
414
414
BT::TestNodeConfig good_config;
415
- good_config.async_delay = std::chrono::milliseconds (300 );
415
+ good_config.async_delay = std::chrono::milliseconds (200 );
416
416
good_config.return_status = NodeStatus::SUCCESS;
417
417
factory.registerNodeType <BT::TestNode>(" GoodTest" , good_config);
418
418
@@ -421,11 +421,77 @@ TEST(FailingParallel, FailingParallel)
421
421
bad_config.return_status = NodeStatus::FAILURE;
422
422
factory.registerNodeType <BT::TestNode>(" BadTest" , bad_config);
423
423
424
+ BT::TestNodeConfig slow_config;
425
+ slow_config.async_delay = std::chrono::milliseconds (300 );
426
+ slow_config.return_status = NodeStatus::SUCCESS;
427
+ factory.registerNodeType <BT::TestNode>(" SlowTest" , slow_config);
428
+
424
429
auto tree = factory.createTreeFromText (xml_text);
425
430
BT::TreeObserver observer (tree);
426
431
427
432
auto state = tree.tickWhileRunning ();
428
433
// since at least one succeeded.
429
434
ASSERT_EQ (NodeStatus::SUCCESS, state);
435
+ ASSERT_EQ ( 1 , observer.getStatistics (" first" ).success_count );
430
436
ASSERT_EQ ( 1 , observer.getStatistics (" second" ).failure_count );
437
+ ASSERT_EQ ( 0 , observer.getStatistics (" third" ).failure_count );
438
+ }
439
+
440
+ TEST (Parallel, ParallelAll)
441
+ {
442
+ using namespace BT ;
443
+
444
+ BehaviorTreeFactory factory;
445
+
446
+ BT::TestNodeConfig good_config;
447
+ good_config.async_delay = std::chrono::milliseconds (300 );
448
+ good_config.return_status = NodeStatus::SUCCESS;
449
+ factory.registerNodeType <BT::TestNode>(" GoodTest" , good_config);
450
+
451
+ BT::TestNodeConfig bad_config;
452
+ bad_config.async_delay = std::chrono::milliseconds (100 );
453
+ bad_config.return_status = NodeStatus::FAILURE;
454
+ factory.registerNodeType <BT::TestNode>(" BadTest" , bad_config);
455
+
456
+ {
457
+ const char * xml_text = R"(
458
+ <root BTCPP_format="4">
459
+ <BehaviorTree ID="MainTree">
460
+ <ParallelAll max_failures="1">
461
+ <BadTest name="first"/>
462
+ <GoodTest name="second"/>
463
+ <GoodTest name="third"/>
464
+ </ParallelAll>
465
+ </BehaviorTree>
466
+ </root> )" ;
467
+ auto tree = factory.createTreeFromText (xml_text);
468
+ BT::TreeObserver observer (tree);
469
+
470
+ auto state = tree.tickWhileRunning ();
471
+ ASSERT_EQ (NodeStatus::FAILURE, state);
472
+ ASSERT_EQ ( 1 , observer.getStatistics (" first" ).failure_count );
473
+ ASSERT_EQ ( 1 , observer.getStatistics (" second" ).success_count );
474
+ ASSERT_EQ ( 1 , observer.getStatistics (" third" ).success_count );
475
+ }
476
+
477
+ {
478
+ const char * xml_text = R"(
479
+ <root BTCPP_format="4">
480
+ <BehaviorTree ID="MainTree">
481
+ <ParallelAll max_failures="2">
482
+ <BadTest name="first"/>
483
+ <GoodTest name="second"/>
484
+ <GoodTest name="third"/>
485
+ </ParallelAll>
486
+ </BehaviorTree>
487
+ </root> )" ;
488
+ auto tree = factory.createTreeFromText (xml_text);
489
+ BT::TreeObserver observer (tree);
490
+
491
+ auto state = tree.tickWhileRunning ();
492
+ ASSERT_EQ (NodeStatus::SUCCESS, state);
493
+ ASSERT_EQ ( 1 , observer.getStatistics (" first" ).failure_count );
494
+ ASSERT_EQ ( 1 , observer.getStatistics (" second" ).success_count );
495
+ ASSERT_EQ ( 1 , observer.getStatistics (" third" ).success_count );
496
+ }
431
497
}
0 commit comments