@@ -23,31 +23,53 @@ NodeStatus ReactiveSequence::tick()
23
23
for (size_t index = 0 ; index < childrenCount (); index++)
24
24
{
25
25
TreeNode* current_child_node = children_nodes_[index];
26
- const NodeStatus child_status = current_child_node-> executeTick () ;
26
+ NodeStatus child_status = NodeStatus::IDLE ;
27
27
28
- switch (child_status)
28
+ if (current_child_node->type () != NodeType::ACTION_ASYNC)
29
+ {
30
+ child_status = current_child_node->executeTick ();
31
+ }
32
+ else
29
33
{
30
- case NodeStatus::RUNNING:
34
+ if (current_child_node-> status () != NodeStatus::RUNNING)
31
35
{
32
- running_count++;
33
- haltChildren (index+1 );
34
- return NodeStatus::RUNNING;
36
+ // if not running already, tick it
37
+ current_child_node->executeTick ();
38
+ do
39
+ {
40
+ child_status = current_child_node->status ();
41
+ } while (child_status == NodeStatus::IDLE);
35
42
}
36
-
37
- case NodeStatus::FAILURE:
43
+ else
38
44
{
39
- haltChildren (0 );
40
- return NodeStatus::FAILURE;
45
+ child_status = NodeStatus::RUNNING;
41
46
}
42
- case NodeStatus::SUCCESS:
43
- {
44
- success_count++;
45
- }break ;
47
+ }
46
48
47
- case NodeStatus::IDLE:
48
- {
49
- throw LogicError (" A child node must never return IDLE" );
50
- }
49
+ switch (child_status)
50
+ {
51
+ case NodeStatus::RUNNING:
52
+ {
53
+ running_count++;
54
+ std::this_thread::sleep_for (milliseconds (3000 ));
55
+ haltChildren (index+1 );
56
+ return NodeStatus::RUNNING;
57
+ }
58
+
59
+ case NodeStatus::FAILURE:
60
+ {
61
+ haltChildren (index+1 );
62
+ return NodeStatus::FAILURE;
63
+ }
64
+ case NodeStatus::SUCCESS:
65
+ {
66
+ success_count++;
67
+ }break ;
68
+
69
+ case NodeStatus::IDLE:
70
+ {
71
+ throw LogicError (" A child node must never return IDLE" );
72
+ }
51
73
} // end switch
52
74
} // end for
53
75
0 commit comments