Skip to content

Commit 6708f63

Browse files
committed
rename haltChildren to resetChildren
1 parent dfc1a1e commit 6708f63

18 files changed

+58
-22
lines changed

include/behaviortree_cpp/control_node.h

Lines changed: 5 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -42,6 +42,7 @@ class ControlNode : public TreeNode
4242

4343
virtual void halt() override;
4444

45+
/// same as resetChildren()
4546
void haltChildren();
4647

4748
[[deprecated("deprecated: please use explicitly haltChildren() or haltChild(i)")]] void
@@ -53,5 +54,9 @@ class ControlNode : public TreeNode
5354
{
5455
return NodeType::CONTROL;
5556
}
57+
58+
/// Set the status of all children to IDLE.
59+
/// also send a halt() signal to all RUNNING children
60+
void resetChildren();
5661
};
5762
} // namespace BT

include/behaviortree_cpp/controls/switch_node.h

Lines changed: 1 addition & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -126,7 +126,7 @@ inline NodeStatus SwitchNode<NUM_CASES>::tick()
126126
}
127127
else
128128
{
129-
haltChildren();
129+
resetChildren();
130130
running_child_ = -1;
131131
}
132132
return ret;

include/behaviortree_cpp/decorator_node.h

Lines changed: 5 additions & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -24,7 +24,7 @@ class DecoratorNode : public TreeNode
2424
/// The method used to interrupt the execution of this node
2525
virtual void halt() override;
2626

27-
/// Halt() the child node
27+
/// Same as resetChild()
2828
void haltChild();
2929

3030
virtual NodeType type() const override
@@ -33,6 +33,10 @@ class DecoratorNode : public TreeNode
3333
}
3434

3535
NodeStatus executeTick() override;
36+
37+
/// Set the status of the child to IDLE.
38+
/// also send a halt() signal to a RUNNING child
39+
void resetChild();
3640
};
3741

3842
/**

src/control_node.cpp

Lines changed: 13 additions & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -31,7 +31,19 @@ size_t ControlNode::childrenCount() const
3131

3232
void ControlNode::halt()
3333
{
34-
haltChildren();
34+
resetChildren();
35+
}
36+
37+
void ControlNode::resetChildren()
38+
{
39+
for (auto child: children_nodes_)
40+
{
41+
if (child->status() == NodeStatus::RUNNING)
42+
{
43+
child->halt();
44+
}
45+
child->resetStatus();
46+
}
3547
}
3648

3749
const std::vector<TreeNode*>& ControlNode::children() const

src/controls/fallback_node.cpp

Lines changed: 2 additions & 2 deletions
Original file line numberDiff line numberDiff line change
@@ -44,7 +44,7 @@ NodeStatus FallbackNode::tick()
4444
return child_status;
4545
}
4646
case NodeStatus::SUCCESS: {
47-
haltChildren();
47+
resetChildren();
4848
current_child_idx_ = 0;
4949
return child_status;
5050
}
@@ -74,7 +74,7 @@ NodeStatus FallbackNode::tick()
7474
// The entire while loop completed. This means that all the children returned FAILURE.
7575
if (current_child_idx_ == children_count)
7676
{
77-
haltChildren();
77+
resetChildren();
7878
current_child_idx_ = 0;
7979
}
8080

src/controls/if_then_else_node.cpp

Lines changed: 1 addition & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -71,7 +71,7 @@ NodeStatus IfThenElseNode::tick()
7171
}
7272
else
7373
{
74-
haltChildren();
74+
resetChildren();
7575
child_idx_ = 0;
7676
return status;
7777
}

src/controls/parallel_node.cpp

Lines changed: 2 additions & 2 deletions
Original file line numberDiff line numberDiff line change
@@ -93,7 +93,7 @@ NodeStatus ParallelNode::tick()
9393
if (success_children_num == successThreshold())
9494
{
9595
skip_list_.clear();
96-
haltChildren();
96+
resetChildren();
9797
return NodeStatus::SUCCESS;
9898
}
9999
}
@@ -109,7 +109,7 @@ NodeStatus ParallelNode::tick()
109109
(failure_children_num == failureThreshold()))
110110
{
111111
skip_list_.clear();
112-
haltChildren();
112+
resetChildren();
113113
return NodeStatus::FAILURE;
114114
}
115115
}

src/controls/reactive_fallback.cpp

Lines changed: 2 additions & 2 deletions
Original file line numberDiff line numberDiff line change
@@ -45,7 +45,7 @@ NodeStatus ReactiveFallback::tick()
4545
break;
4646

4747
case NodeStatus::SUCCESS: {
48-
haltChildren();
48+
resetChildren();
4949
return NodeStatus::SUCCESS;
5050
}
5151

@@ -62,7 +62,7 @@ NodeStatus ReactiveFallback::tick()
6262

6363
if (failure_count == childrenCount())
6464
{
65-
haltChildren();
65+
resetChildren();
6666
return NodeStatus::FAILURE;
6767
}
6868

src/controls/reactive_sequence.cpp

Lines changed: 2 additions & 2 deletions
Original file line numberDiff line numberDiff line change
@@ -43,7 +43,7 @@ NodeStatus ReactiveSequence::tick()
4343
}
4444

4545
case NodeStatus::FAILURE: {
46-
haltChildren();
46+
resetChildren();
4747
return NodeStatus::FAILURE;
4848
}
4949
case NodeStatus::SUCCESS: {
@@ -64,7 +64,7 @@ NodeStatus ReactiveSequence::tick()
6464

6565
if (success_count == childrenCount())
6666
{
67-
haltChildren();
67+
resetChildren();
6868

6969
// Skip if ALL the nodes have been skipped
7070
return status() == (NodeStatus::RUNNING) ? NodeStatus::SUCCESS : NodeStatus::SKIPPED;

src/controls/sequence_node.cpp

Lines changed: 2 additions & 2 deletions
Original file line numberDiff line numberDiff line change
@@ -51,7 +51,7 @@ NodeStatus SequenceNode::tick()
5151
}
5252
case NodeStatus::FAILURE: {
5353
// Reset on failure
54-
haltChildren();
54+
resetChildren();
5555
current_child_idx_ = 0;
5656
return child_status;
5757
}
@@ -83,7 +83,7 @@ NodeStatus SequenceNode::tick()
8383
// The entire while loop completed. This means that all the children returned SUCCESS.
8484
if (current_child_idx_ == children_count)
8585
{
86-
haltChildren();
86+
resetChildren();
8787
current_child_idx_ = 0;
8888
}
8989
// Skip if ALL the nodes have been skipped

0 commit comments

Comments
 (0)