@@ -66,12 +66,15 @@ struct ComplexSequenceTest : testing::Test
6666struct SequenceTripleActionTest : testing::Test
6767{
6868 BT::SequenceNode root;
69+ BT::ConditionTestNode condition;
6970 BT::AsyncActionTest action_1;
7071 BT::SyncActionTest action_2;
7172 BT::AsyncActionTest action_3;
7273
73- SequenceTripleActionTest () : root(" root_sequence" ), action_1(" action_1" ), action_2(" action_2" ), action_3(" action_3" )
74+ SequenceTripleActionTest () : root(" root_sequence" ), condition(" condition" ),
75+ action_1 (" action_1" ), action_2(" action_2" ), action_3(" action_3" )
7476 {
77+ root.addChild (&condition);
7578 root.addChild (&action_1);
7679 root.addChild (&action_2);
7780 root.addChild (&action_3);
@@ -247,21 +250,7 @@ TEST_F(SequenceTripleActionTest, TripleAction)
247250
248251 action_1.setTime (3 );
249252 action_3.setTime (3 );
250- // the sequence is supposed to finish in (200 ms * 3) = 600 ms
251-
252- int count_1 = 0 , count_2 = 0 , count_3 = 0 ;
253-
254- auto sub1 = action_1.subscribeToStatusChange ([&](TimePoint, const TreeNode&, NodeStatus, NodeStatus status) {
255- if (status == NodeStatus::SUCCESS) count_1++;
256- });
257-
258- auto sub2 = action_2.subscribeToStatusChange ([&](TimePoint, const TreeNode&, NodeStatus, NodeStatus status) {
259- if (status == NodeStatus::SUCCESS) count_2++;
260- });
261-
262- auto sub3 = action_3.subscribeToStatusChange ([&](TimePoint, const TreeNode&, NodeStatus, NodeStatus status) {
263- if (status == NodeStatus::SUCCESS) count_3++;
264- });
253+ // the sequence is supposed to finish in (300 ms * 2) = 600 ms
265254
266255 // first tick
267256 NodeStatus state = root.executeTick ();
@@ -279,9 +268,14 @@ TEST_F(SequenceTripleActionTest, TripleAction)
279268 }
280269
281270 ASSERT_EQ (NodeStatus::SUCCESS, state);
282- ASSERT_TRUE (count_1 == 1 );
283- ASSERT_TRUE (count_2 == 1 );
284- ASSERT_TRUE (count_3 == 1 );
271+
272+ // Condition is called many times
273+ ASSERT_NE (condition.tickCount (), 30 );
274+ // all the actions are called only once
275+ ASSERT_EQ (action_1.tickCount (), 1 );
276+ ASSERT_EQ (action_2.tickCount (), 1 );
277+ ASSERT_EQ (action_3.tickCount (), 1 );
278+
285279 ASSERT_EQ (NodeStatus::IDLE, action_1.status ());
286280 ASSERT_EQ (NodeStatus::IDLE, action_2.status ());
287281 ASSERT_EQ (NodeStatus::IDLE, action_3.status ());
0 commit comments