Skip to content

Commit ac68234

Browse files
committed
fix ParallelAll
1 parent b376a87 commit ac68234

File tree

3 files changed

+73
-6
lines changed

3 files changed

+73
-6
lines changed

src/bt_factory.cpp

Lines changed: 1 addition & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -633,7 +633,7 @@ NodeStatus Tree::tickRoot(TickOption opt, std::chrono::milliseconds sleep_time)
633633
status = rootNode()->executeTick();
634634
}
635635

636-
if (status == NodeStatus::SUCCESS || status == NodeStatus::FAILURE)
636+
if (isStatusCompleted(status))
637637
{
638638
rootNode()->resetStatus();
639639
}

src/controls/parallel_all_node.cpp

Lines changed: 3 additions & 2 deletions
Original file line numberDiff line numberDiff line change
@@ -93,9 +93,10 @@ NodeStatus ParallelAllNode::tick()
9393
// DONE
9494
haltChildren();
9595
completed_list_.clear();
96+
auto const status = (failure_count_ >= failure_threshold_) ?
97+
NodeStatus::FAILURE : NodeStatus::SUCCESS;
9698
failure_count_ = 0;
97-
return (failure_count_ >= failure_threshold_) ? NodeStatus::FAILURE :
98-
NodeStatus::SUCCESS;
99+
return status;
99100
}
100101

101102
// Some children haven't finished, yet.

tests/gtest_parallel.cpp

Lines changed: 69 additions & 3 deletions
Original file line numberDiff line numberDiff line change
@@ -395,15 +395,15 @@ TEST_F(ComplexParallelTest, ConditionRightFalseAction1Done)
395395
ASSERT_EQ(NodeStatus::SUCCESS, state);
396396
}
397397

398-
TEST(FailingParallel, FailingParallel)
398+
TEST(Parallel, FailingParallel)
399399
{
400400
static const char* xml_text = R"(
401401
<root BTCPP_format="4">
402402
<BehaviorTree ID="MainTree">
403403
<Parallel name="parallel" success_count="1" failure_count="3">
404404
<GoodTest name="first"/>
405405
<BadTest name="second"/>
406-
<GoodTest name="third"/>
406+
<SlowTest name="third"/>
407407
</Parallel>
408408
</BehaviorTree>
409409
</root> )";
@@ -412,7 +412,7 @@ TEST(FailingParallel, FailingParallel)
412412
BehaviorTreeFactory factory;
413413

414414
BT::TestNodeConfig good_config;
415-
good_config.async_delay = std::chrono::milliseconds(300);
415+
good_config.async_delay = std::chrono::milliseconds(200);
416416
good_config.return_status = NodeStatus::SUCCESS;
417417
factory.registerNodeType<BT::TestNode>("GoodTest", good_config);
418418

@@ -421,11 +421,77 @@ TEST(FailingParallel, FailingParallel)
421421
bad_config.return_status = NodeStatus::FAILURE;
422422
factory.registerNodeType<BT::TestNode>("BadTest", bad_config);
423423

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+
424429
auto tree = factory.createTreeFromText(xml_text);
425430
BT::TreeObserver observer(tree);
426431

427432
auto state = tree.tickWhileRunning();
428433
// since at least one succeeded.
429434
ASSERT_EQ(NodeStatus::SUCCESS, state);
435+
ASSERT_EQ( 1, observer.getStatistics("first").success_count);
430436
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+
}
431497
}

0 commit comments

Comments
 (0)