Thanks to visit codestin.com
Credit goes to github.com

Skip to content

Commit 3678297

Browse files
committed
change API of haltChildren()
1 parent 1d9561d commit 3678297

File tree

9 files changed

+46
-28
lines changed

9 files changed

+46
-28
lines changed

include/behaviortree_cpp_v3/control_node.h

Lines changed: 4 additions & 2 deletions
Original file line numberDiff line numberDiff line change
@@ -43,8 +43,10 @@ class ControlNode : public TreeNode
4343

4444
virtual void halt() override;
4545

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);
4850

4951
virtual NodeType type() const override final
5052
{

include/behaviortree_cpp_v3/controls/switch_node.h

Lines changed: 2 additions & 2 deletions
Original file line numberDiff line numberDiff line change
@@ -101,7 +101,7 @@ NodeStatus SwitchNode<NUM_CASES>::tick()
101101
// if another one was running earlier, halt it
102102
if( running_child_ != -1 && running_child_ != child_index)
103103
{
104-
children_nodes_[running_child_]->halt();
104+
haltChild(running_child_);
105105
}
106106

107107
auto& selected_child = children_nodes_[child_index];
@@ -111,7 +111,7 @@ NodeStatus SwitchNode<NUM_CASES>::tick()
111111
running_child_ = child_index;
112112
}
113113
else{
114-
selected_child->halt();
114+
haltChildren();
115115
running_child_ = -1;
116116
}
117117
return ret;

src/control_node.cpp

Lines changed: 14 additions & 9 deletions
Original file line numberDiff line numberDiff line change
@@ -32,7 +32,7 @@ size_t ControlNode::childrenCount() const
3232

3333
void ControlNode::halt()
3434
{
35-
haltChildren(0);
35+
haltChildren();
3636
setStatus(NodeStatus::IDLE);
3737
}
3838

@@ -41,16 +41,21 @@ const std::vector<TreeNode*>& ControlNode::children() const
4141
return children_nodes_;
4242
}
4343

44-
void ControlNode::haltChildren(size_t i)
44+
void ControlNode::haltChild(size_t i)
4545
{
46-
for (size_t j = i; j < children_nodes_.size(); j++)
46+
auto child = children_nodes_[i];
47+
if (child->status() == NodeStatus::RUNNING)
4748
{
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);
5459
}
5560
}
5661

src/controls/fallback_node.cpp

Lines changed: 2 additions & 2 deletions
Original file line numberDiff line numberDiff line change
@@ -42,7 +42,7 @@ NodeStatus FallbackNode::tick()
4242
}
4343
case NodeStatus::SUCCESS:
4444
{
45-
haltChildren(0);
45+
haltChildren();
4646
current_child_idx_ = 0;
4747
return child_status;
4848
}
@@ -62,7 +62,7 @@ NodeStatus FallbackNode::tick()
6262
// The entire while loop completed. This means that all the children returned FAILURE.
6363
if (current_child_idx_ == children_count)
6464
{
65-
haltChildren(0);
65+
haltChildren();
6666
current_child_idx_ = 0;
6767
}
6868

src/controls/parallel_node.cpp

Lines changed: 2 additions & 2 deletions
Original file line numberDiff line numberDiff line change
@@ -83,7 +83,7 @@ NodeStatus ParallelNode::tick()
8383
if (success_childred_num == threshold_)
8484
{
8585
skip_list_.clear();
86-
haltChildren(0);
86+
haltChildren();
8787
return NodeStatus::SUCCESS;
8888
}
8989
} break;
@@ -99,7 +99,7 @@ NodeStatus ParallelNode::tick()
9999
if (failure_childred_num > children_count - threshold_)
100100
{
101101
skip_list_.clear();
102-
haltChildren(0);
102+
haltChildren();
103103
return NodeStatus::FAILURE;
104104
}
105105
} break;

src/controls/reactive_fallback.cpp

Lines changed: 6 additions & 3 deletions
Original file line numberDiff line numberDiff line change
@@ -28,7 +28,10 @@ NodeStatus ReactiveFallback::tick()
2828
{
2929
case NodeStatus::RUNNING:
3030
{
31-
haltChildren(index+1);
31+
for(int i=index+1; i < childrenCount(); i++)
32+
{
33+
haltChild(i);
34+
}
3235
return NodeStatus::RUNNING;
3336
}
3437

@@ -39,7 +42,7 @@ NodeStatus ReactiveFallback::tick()
3942

4043
case NodeStatus::SUCCESS:
4144
{
42-
haltChildren(0);
45+
haltChildren();
4346
return NodeStatus::SUCCESS;
4447
}
4548

@@ -52,7 +55,7 @@ NodeStatus ReactiveFallback::tick()
5255

5356
if( failure_count == childrenCount() )
5457
{
55-
haltChildren(0);
58+
haltChildren();
5659
return NodeStatus::FAILURE;
5760
}
5861

src/controls/reactive_sequence.cpp

Lines changed: 7 additions & 3 deletions
Original file line numberDiff line numberDiff line change
@@ -30,13 +30,17 @@ NodeStatus ReactiveSequence::tick()
3030
case NodeStatus::RUNNING:
3131
{
3232
running_count++;
33-
haltChildren(index+1);
33+
34+
for(int i=index+1; i < childrenCount(); i++)
35+
{
36+
haltChild(i);
37+
}
3438
return NodeStatus::RUNNING;
3539
}
3640

3741
case NodeStatus::FAILURE:
3842
{
39-
haltChildren(0);
43+
haltChildren();
4044
return NodeStatus::FAILURE;
4145
}
4246
case NodeStatus::SUCCESS:
@@ -53,7 +57,7 @@ NodeStatus ReactiveSequence::tick()
5357

5458
if( success_count == childrenCount())
5559
{
56-
haltChildren(0);
60+
haltChildren();
5761
return NodeStatus::SUCCESS;
5862
}
5963
return NodeStatus::RUNNING;

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
case NodeStatus::FAILURE:
5252
{
5353
// Reset on failure
54-
haltChildren(0);
54+
haltChildren();
5555
current_child_idx_ = 0;
5656
return child_status;
5757
}
@@ -71,7 +71,7 @@ NodeStatus SequenceNode::tick()
7171
// The entire while loop completed. This means that all the children returned SUCCESS.
7272
if (current_child_idx_ == children_count)
7373
{
74-
haltChildren(0);
74+
haltChildren();
7575
current_child_idx_ = 0;
7676
}
7777
return NodeStatus::SUCCESS;

src/controls/sequence_star_node.cpp

Lines changed: 7 additions & 3 deletions
Original file line numberDiff line numberDiff line change
@@ -42,8 +42,12 @@ NodeStatus SequenceStarNode::tick()
4242
}
4343
case NodeStatus::FAILURE:
4444
{
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+
4751
return child_status;
4852
}
4953
case NodeStatus::SUCCESS:
@@ -62,7 +66,7 @@ NodeStatus SequenceStarNode::tick()
6266
// The entire while loop completed. This means that all the children returned SUCCESS.
6367
if (current_child_idx_ == children_count)
6468
{
65-
haltChildren(0);
69+
haltChildren();
6670
current_child_idx_ = 0;
6771
}
6872
return NodeStatus::SUCCESS;

0 commit comments

Comments
 (0)