File tree Expand file tree Collapse file tree 9 files changed +46
-28
lines changed
include/behaviortree_cpp_v3 Expand file tree Collapse file tree 9 files changed +46
-28
lines changed Original file line number Diff line number Diff line change @@ -43,8 +43,10 @@ class ControlNode : public TreeNode
43
43
44
44
virtual void halt () override ;
45
45
46
- // / call halt() for all the children in the range [i, childrenCount() )
47
- void haltChildren (size_t i);
46
+
47
+ void haltChildren ();
48
+
49
+ void haltChild (size_t i);
48
50
49
51
virtual NodeType type () const override final
50
52
{
Original file line number Diff line number Diff line change @@ -101,7 +101,7 @@ NodeStatus SwitchNode<NUM_CASES>::tick()
101
101
// if another one was running earlier, halt it
102
102
if ( running_child_ != -1 && running_child_ != child_index)
103
103
{
104
- children_nodes_[running_child_]-> halt ( );
104
+ haltChild (running_child_ );
105
105
}
106
106
107
107
auto & selected_child = children_nodes_[child_index];
@@ -111,7 +111,7 @@ NodeStatus SwitchNode<NUM_CASES>::tick()
111
111
running_child_ = child_index;
112
112
}
113
113
else {
114
- selected_child-> halt ();
114
+ haltChildren ();
115
115
running_child_ = -1 ;
116
116
}
117
117
return ret;
Original file line number Diff line number Diff line change @@ -32,7 +32,7 @@ size_t ControlNode::childrenCount() const
32
32
33
33
void ControlNode::halt ()
34
34
{
35
- haltChildren (0 );
35
+ haltChildren ();
36
36
setStatus (NodeStatus::IDLE);
37
37
}
38
38
@@ -41,16 +41,21 @@ const std::vector<TreeNode*>& ControlNode::children() const
41
41
return children_nodes_;
42
42
}
43
43
44
- void ControlNode::haltChildren (size_t i)
44
+ void ControlNode::haltChild (size_t i)
45
45
{
46
- for (size_t j = i; j < children_nodes_.size (); j++)
46
+ auto child = children_nodes_[i];
47
+ if (child->status () == NodeStatus::RUNNING)
47
48
{
48
- auto child = children_nodes_[j];
49
- if (child->status () == NodeStatus::RUNNING)
50
- {
51
- child->halt ();
52
- }
53
- child->setStatus (NodeStatus::IDLE);
49
+ child->halt ();
50
+ }
51
+ child->setStatus (NodeStatus::IDLE);
52
+ }
53
+
54
+ void ControlNode::haltChildren ()
55
+ {
56
+ for (size_t i = 0 ; i < children_nodes_.size (); i++)
57
+ {
58
+ haltChild (i);
54
59
}
55
60
}
56
61
Original file line number Diff line number Diff line change @@ -42,7 +42,7 @@ NodeStatus FallbackNode::tick()
42
42
}
43
43
case NodeStatus::SUCCESS:
44
44
{
45
- haltChildren (0 );
45
+ haltChildren ();
46
46
current_child_idx_ = 0 ;
47
47
return child_status;
48
48
}
@@ -62,7 +62,7 @@ NodeStatus FallbackNode::tick()
62
62
// The entire while loop completed. This means that all the children returned FAILURE.
63
63
if (current_child_idx_ == children_count)
64
64
{
65
- haltChildren (0 );
65
+ haltChildren ();
66
66
current_child_idx_ = 0 ;
67
67
}
68
68
Original file line number Diff line number Diff line change @@ -83,7 +83,7 @@ NodeStatus ParallelNode::tick()
83
83
if (success_childred_num == threshold_)
84
84
{
85
85
skip_list_.clear ();
86
- haltChildren (0 );
86
+ haltChildren ();
87
87
return NodeStatus::SUCCESS;
88
88
}
89
89
} break ;
@@ -99,7 +99,7 @@ NodeStatus ParallelNode::tick()
99
99
if (failure_childred_num > children_count - threshold_)
100
100
{
101
101
skip_list_.clear ();
102
- haltChildren (0 );
102
+ haltChildren ();
103
103
return NodeStatus::FAILURE;
104
104
}
105
105
} break ;
Original file line number Diff line number Diff line change @@ -28,7 +28,10 @@ NodeStatus ReactiveFallback::tick()
28
28
{
29
29
case NodeStatus::RUNNING:
30
30
{
31
- haltChildren (index+1 );
31
+ for (int i=index+1 ; i < childrenCount (); i++)
32
+ {
33
+ haltChild (i);
34
+ }
32
35
return NodeStatus::RUNNING;
33
36
}
34
37
@@ -39,7 +42,7 @@ NodeStatus ReactiveFallback::tick()
39
42
40
43
case NodeStatus::SUCCESS:
41
44
{
42
- haltChildren (0 );
45
+ haltChildren ();
43
46
return NodeStatus::SUCCESS;
44
47
}
45
48
@@ -52,7 +55,7 @@ NodeStatus ReactiveFallback::tick()
52
55
53
56
if ( failure_count == childrenCount () )
54
57
{
55
- haltChildren (0 );
58
+ haltChildren ();
56
59
return NodeStatus::FAILURE;
57
60
}
58
61
Original file line number Diff line number Diff line change @@ -30,13 +30,17 @@ NodeStatus ReactiveSequence::tick()
30
30
case NodeStatus::RUNNING:
31
31
{
32
32
running_count++;
33
- haltChildren (index+1 );
33
+
34
+ for (int i=index+1 ; i < childrenCount (); i++)
35
+ {
36
+ haltChild (i);
37
+ }
34
38
return NodeStatus::RUNNING;
35
39
}
36
40
37
41
case NodeStatus::FAILURE:
38
42
{
39
- haltChildren (0 );
43
+ haltChildren ();
40
44
return NodeStatus::FAILURE;
41
45
}
42
46
case NodeStatus::SUCCESS:
@@ -53,7 +57,7 @@ NodeStatus ReactiveSequence::tick()
53
57
54
58
if ( success_count == childrenCount ())
55
59
{
56
- haltChildren (0 );
60
+ haltChildren ();
57
61
return NodeStatus::SUCCESS;
58
62
}
59
63
return NodeStatus::RUNNING;
Original file line number Diff line number Diff line change @@ -51,7 +51,7 @@ NodeStatus SequenceNode::tick()
51
51
case NodeStatus::FAILURE:
52
52
{
53
53
// Reset on failure
54
- haltChildren (0 );
54
+ haltChildren ();
55
55
current_child_idx_ = 0 ;
56
56
return child_status;
57
57
}
@@ -71,7 +71,7 @@ NodeStatus SequenceNode::tick()
71
71
// The entire while loop completed. This means that all the children returned SUCCESS.
72
72
if (current_child_idx_ == children_count)
73
73
{
74
- haltChildren (0 );
74
+ haltChildren ();
75
75
current_child_idx_ = 0 ;
76
76
}
77
77
return NodeStatus::SUCCESS;
Original file line number Diff line number Diff line change @@ -42,8 +42,12 @@ NodeStatus SequenceStarNode::tick()
42
42
}
43
43
case NodeStatus::FAILURE:
44
44
{
45
- // DO NOT reset on failure
46
- haltChildren (current_child_idx_);
45
+ // DO NOT reset current_child_idx_ on failure
46
+ for (int i=current_child_idx_; i < childrenCount (); i++)
47
+ {
48
+ haltChild (i);
49
+ }
50
+
47
51
return child_status;
48
52
}
49
53
case NodeStatus::SUCCESS:
@@ -62,7 +66,7 @@ NodeStatus SequenceStarNode::tick()
62
66
// The entire while loop completed. This means that all the children returned SUCCESS.
63
67
if (current_child_idx_ == children_count)
64
68
{
65
- haltChildren (0 );
69
+ haltChildren ();
66
70
current_child_idx_ = 0 ;
67
71
}
68
72
return NodeStatus::SUCCESS;
You can’t perform that action at this time.
0 commit comments