Skip to content

Commit 957a7f8

Browse files
committed
fix the "all_skipped" logic
1 parent 2a8a226 commit 957a7f8

File tree

11 files changed

+49
-39
lines changed

11 files changed

+49
-39
lines changed

include/behaviortree_cpp/controls/fallback_node.h

Lines changed: 1 addition & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -40,7 +40,7 @@ class FallbackNode : public ControlNode
4040

4141
private:
4242
size_t current_child_idx_;
43-
bool all_skipped_ = true;
43+
size_t skipped_count_ = 0;
4444
bool asynch_ = false;
4545

4646
virtual BT::NodeStatus tick() override;

include/behaviortree_cpp/controls/sequence_node.h

Lines changed: 1 addition & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -42,7 +42,7 @@ class SequenceNode : public ControlNode
4242

4343
private:
4444
size_t current_child_idx_;
45-
bool all_skipped_ = true;
45+
size_t skipped_count_ = 0;
4646
bool asynch_ = false;
4747

4848
virtual BT::NodeStatus tick() override;

include/behaviortree_cpp/controls/sequence_with_memory_node.h

Lines changed: 1 addition & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -42,7 +42,7 @@ class SequenceWithMemory : public ControlNode
4242

4343
private:
4444
size_t current_child_idx_;
45-
bool all_skipped_ = true;
45+
size_t skipped_count_ = 0;
4646

4747
virtual BT::NodeStatus tick() override;
4848
};

include/behaviortree_cpp/decorators/repeat_node.h

Lines changed: 0 additions & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -50,7 +50,6 @@ class RepeatNode : public DecoratorNode
5050
private:
5151
int num_cycles_;
5252
int repeat_count_;
53-
bool all_skipped_ = true;
5453

5554
bool read_parameter_from_ports_;
5655
static constexpr const char* NUM_CYCLES = "num_cycles";

include/behaviortree_cpp/decorators/retry_node.h

Lines changed: 0 additions & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -56,7 +56,6 @@ class RetryNode : public DecoratorNode
5656
private:
5757
int max_attempts_;
5858
int try_count_;
59-
bool all_skipped_ = true;
6059

6160
bool read_parameter_from_ports_;
6261
static constexpr const char* NUM_ATTEMPTS = "num_attempts";

src/controls/fallback_node.cpp

Lines changed: 3 additions & 6 deletions
Original file line numberDiff line numberDiff line change
@@ -18,7 +18,6 @@ namespace BT
1818
FallbackNode::FallbackNode(const std::string& name, bool make_asynch)
1919
: ControlNode::ControlNode(name, {})
2020
, current_child_idx_(0)
21-
, all_skipped_(true)
2221
, asynch_(make_asynch)
2322
{
2423
if(asynch_)
@@ -33,7 +32,7 @@ NodeStatus FallbackNode::tick()
3332

3433
if(status() == NodeStatus::IDLE)
3534
{
36-
all_skipped_ = true;
35+
skipped_count_ = 0;
3736
}
3837

3938
setStatus(NodeStatus::RUNNING);
@@ -45,9 +44,6 @@ NodeStatus FallbackNode::tick()
4544
auto prev_status = current_child_node->status();
4645
const NodeStatus child_status = current_child_node->executeTick();
4746

48-
// switch to RUNNING state as soon as you find an active child
49-
all_skipped_ &= (child_status == NodeStatus::SKIPPED);
50-
5147
switch(child_status)
5248
{
5349
case NodeStatus::RUNNING: {
@@ -73,6 +69,7 @@ NodeStatus FallbackNode::tick()
7369
case NodeStatus::SKIPPED: {
7470
// It was requested to skip this node
7571
current_child_idx_++;
72+
skipped_count_++;
7673
}
7774
break;
7875
case NodeStatus::IDLE: {
@@ -89,7 +86,7 @@ NodeStatus FallbackNode::tick()
8986
}
9087

9188
// Skip if ALL the nodes have been skipped
92-
return all_skipped_ ? NodeStatus::SKIPPED : NodeStatus::FAILURE;
89+
return (skipped_count_ == children_count) ? NodeStatus::SKIPPED : NodeStatus::FAILURE;
9390
}
9491

9592
void FallbackNode::halt()

src/controls/sequence_node.cpp

Lines changed: 3 additions & 6 deletions
Original file line numberDiff line numberDiff line change
@@ -18,7 +18,6 @@ namespace BT
1818
SequenceNode::SequenceNode(const std::string& name, bool make_async)
1919
: ControlNode::ControlNode(name, {})
2020
, current_child_idx_(0)
21-
, all_skipped_(true)
2221
, asynch_(make_async)
2322
{
2423
if(asynch_)
@@ -39,7 +38,7 @@ NodeStatus SequenceNode::tick()
3938

4039
if(status() == NodeStatus::IDLE)
4140
{
42-
all_skipped_ = true;
41+
skipped_count_ = 0;
4342
}
4443

4544
setStatus(NodeStatus::RUNNING);
@@ -51,9 +50,6 @@ NodeStatus SequenceNode::tick()
5150
auto prev_status = current_child_node->status();
5251
const NodeStatus child_status = current_child_node->executeTick();
5352

54-
// switch to RUNNING state as soon as you find an active child
55-
all_skipped_ &= (child_status == NodeStatus::SKIPPED);
56-
5753
switch(child_status)
5854
{
5955
case NodeStatus::RUNNING: {
@@ -81,6 +77,7 @@ NodeStatus SequenceNode::tick()
8177
case NodeStatus::SKIPPED: {
8278
// It was requested to skip this node
8379
current_child_idx_++;
80+
skipped_count_++;
8481
}
8582
break;
8683

@@ -97,7 +94,7 @@ NodeStatus SequenceNode::tick()
9794
current_child_idx_ = 0;
9895
}
9996
// Skip if ALL the nodes have been skipped
100-
return all_skipped_ ? NodeStatus::SKIPPED : NodeStatus::SUCCESS;
97+
return (skipped_count_ == children_count) ? NodeStatus::SKIPPED : NodeStatus::SUCCESS;
10198
}
10299

103100
} // namespace BT

src/controls/sequence_with_memory_node.cpp

Lines changed: 3 additions & 5 deletions
Original file line numberDiff line numberDiff line change
@@ -27,7 +27,7 @@ NodeStatus SequenceWithMemory::tick()
2727

2828
if(status() == NodeStatus::IDLE)
2929
{
30-
all_skipped_ = true;
30+
skipped_count_ = 0;
3131
}
3232
setStatus(NodeStatus::RUNNING);
3333

@@ -38,9 +38,6 @@ NodeStatus SequenceWithMemory::tick()
3838
auto prev_status = current_child_node->status();
3939
const NodeStatus child_status = current_child_node->executeTick();
4040

41-
// switch to RUNNING state as soon as you find an active child
42-
all_skipped_ &= (child_status == NodeStatus::SKIPPED);
43-
4441
switch(child_status)
4542
{
4643
case NodeStatus::RUNNING: {
@@ -71,6 +68,7 @@ NodeStatus SequenceWithMemory::tick()
7168
case NodeStatus::SKIPPED: {
7269
// It was requested to skip this node
7370
current_child_idx_++;
71+
skipped_count_++;
7472
}
7573
break;
7674

@@ -87,7 +85,7 @@ NodeStatus SequenceWithMemory::tick()
8785
current_child_idx_ = 0;
8886
}
8987
// Skip if ALL the nodes have been skipped
90-
return all_skipped_ ? NodeStatus::SKIPPED : NodeStatus::SUCCESS;
88+
return (skipped_count_ == children_count) ? NodeStatus::SKIPPED : NodeStatus::SUCCESS;
9189
}
9290

9391
void SequenceWithMemory::halt()

src/decorators/repeat_node.cpp

Lines changed: 1 addition & 8 deletions
Original file line numberDiff line numberDiff line change
@@ -43,20 +43,13 @@ NodeStatus RepeatNode::tick()
4343
}
4444

4545
bool do_loop = repeat_count_ < num_cycles_ || num_cycles_ == -1;
46-
if(status() == NodeStatus::IDLE)
47-
{
48-
all_skipped_ = true;
49-
}
5046
setStatus(NodeStatus::RUNNING);
5147

5248
while(do_loop)
5349
{
5450
NodeStatus const prev_status = child_node_->status();
5551
NodeStatus child_status = child_node_->executeTick();
5652

57-
// switch to RUNNING state as soon as you find an active child
58-
all_skipped_ &= (child_status == NodeStatus::SKIPPED);
59-
6053
switch(child_status)
6154
{
6255
case NodeStatus::SUCCESS: {
@@ -99,7 +92,7 @@ NodeStatus RepeatNode::tick()
9992
}
10093

10194
repeat_count_ = 0;
102-
return all_skipped_ ? NodeStatus::SKIPPED : NodeStatus::SUCCESS;
95+
return NodeStatus::SUCCESS;
10396
}
10497

10598
void RepeatNode::halt()

src/decorators/retry_node.cpp

Lines changed: 1 addition & 9 deletions
Original file line numberDiff line numberDiff line change
@@ -50,21 +50,13 @@ NodeStatus RetryNode::tick()
5050
}
5151

5252
bool do_loop = try_count_ < max_attempts_ || max_attempts_ == -1;
53-
54-
if(status() == NodeStatus::IDLE)
55-
{
56-
all_skipped_ = true;
57-
}
5853
setStatus(NodeStatus::RUNNING);
5954

6055
while(do_loop)
6156
{
6257
NodeStatus prev_status = child_node_->status();
6358
NodeStatus child_status = child_node_->executeTick();
6459

65-
// switch to RUNNING state as soon as you find an active child
66-
all_skipped_ &= (child_status == NodeStatus::SKIPPED);
67-
6860
switch(child_status)
6961
{
7062
case NodeStatus::SUCCESS: {
@@ -107,7 +99,7 @@ NodeStatus RetryNode::tick()
10799
}
108100

109101
try_count_ = 0;
110-
return all_skipped_ ? NodeStatus::SKIPPED : NodeStatus::FAILURE;
102+
return NodeStatus::FAILURE;
111103
}
112104

113105
} // namespace BT

tests/gtest_preconditions.cpp

Lines changed: 35 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -363,3 +363,38 @@ TEST(Preconditions, Remapping)
363363
ASSERT_EQ(counters[0], 1);
364364
ASSERT_EQ(counters[1], 3);
365365
}
366+
367+
368+
TEST(Preconditions, WhileCallsOnHalt)
369+
{
370+
static constexpr auto xml_text = R"(
371+
<root BTCPP_format="4">
372+
373+
<BehaviorTree ID="Main">
374+
<Sequence>
375+
<KeepRunning _while="A==1" _onHalted="B=69" />
376+
</Sequence>
377+
</BehaviorTree>
378+
</root>
379+
)";
380+
381+
BehaviorTreeFactory factory;
382+
383+
factory.registerNodeType<KeepRunning>("KeepRunning");
384+
factory.registerBehaviorTreeFromText(xml_text);
385+
auto tree = factory.createTree("Main");
386+
387+
tree.rootBlackboard()->set("A", 1);
388+
tree.rootBlackboard()->set("B", 0);
389+
auto status = tree.tickOnce();
390+
391+
ASSERT_EQ(status, BT::NodeStatus::RUNNING);
392+
ASSERT_EQ(tree.rootBlackboard()->get<int>("B"), 0);
393+
394+
// trigger halt
395+
tree.rootBlackboard()->set("A", 0);
396+
status = tree.tickOnce();
397+
398+
ASSERT_EQ(status, BT::NodeStatus::SKIPPED);
399+
ASSERT_EQ(tree.rootBlackboard()->get<int>("B"), 69);
400+
}

0 commit comments

Comments
 (0)