Skip to content

Commit 10b1227

Browse files
committed
fix issue #615 : don't execute preconditions if state is RUNNING
1 parent 93c661c commit 10b1227

File tree

2 files changed

+79
-3
lines changed

2 files changed

+79
-3
lines changed

src/tree_node.cpp

Lines changed: 6 additions & 3 deletions
Original file line numberDiff line numberDiff line change
@@ -128,7 +128,10 @@ NodeStatus TreeNode::executeTick()
128128
}
129129
}
130130

131-
setStatus(new_status);
131+
// preserve the IDLE state if skipped, but communicate SKIPPED to parent
132+
if(new_status != NodeStatus::SKIPPED) {
133+
setStatus(new_status);
134+
}
132135
return new_status;
133136
}
134137

@@ -192,7 +195,7 @@ Expected<NodeStatus> TreeNode::checkPreConditions()
192195
if (result.cast<bool>())
193196
{
194197
// Some preconditions are applied only when the node is started
195-
if (!isStatusCompleted(_p->status))
198+
if (_p->status == NodeStatus::IDLE)
196199
{
197200
if (preID == PreCond::FAILURE_IF)
198201
{
@@ -212,7 +215,7 @@ Expected<NodeStatus> TreeNode::checkPreConditions()
212215
{
213216
if (preID == PreCond::WHILE_TRUE)
214217
{
215-
if (_p->status == NodeStatus::RUNNING)
218+
if (!isStatusCompleted(_p->status))
216219
{
217220
halt();
218221
}

tests/gtest_preconditions.cpp

Lines changed: 73 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -225,3 +225,76 @@ TEST(Preconditions, Issue585)
225225
auto coro = dynamic_cast<CoroTestNode*>(tree.subtrees.front()->nodes.back().get());
226226
ASSERT_EQ(coro->times_ticked, 0);
227227
}
228+
229+
TEST(Preconditions, Issue615_NoSkipWhenRunning_A)
230+
{
231+
static constexpr auto xml_text = R"(
232+
<root BTCPP_format="4">
233+
<BehaviorTree>
234+
<KeepRunningUntilFailure _skipIf="check == true">
235+
<AlwaysSuccess/>
236+
</KeepRunningUntilFailure>
237+
</BehaviorTree>
238+
</root> )";
239+
240+
BehaviorTreeFactory factory;
241+
auto tree = factory.createTreeFromText(xml_text);
242+
243+
tree.rootBlackboard()->set("check", false);
244+
ASSERT_EQ( tree.tickOnce(), NodeStatus::RUNNING );
245+
246+
// the precondition should NOT be called, because
247+
// KeepRunningUntilFailure is in RUNNING state
248+
tree.rootBlackboard()->set("check", true);
249+
ASSERT_EQ( tree.tickOnce(), NodeStatus::RUNNING );
250+
}
251+
252+
class KeepRunning : public BT::StatefulActionNode
253+
{
254+
public:
255+
KeepRunning(const std::string& name, const BT::NodeConfig& config) :
256+
BT::StatefulActionNode(name, config){}
257+
258+
static BT::PortsList providedPorts() {
259+
return {};
260+
}
261+
262+
BT::NodeStatus onStart() override {
263+
return BT::NodeStatus::RUNNING;
264+
}
265+
266+
BT::NodeStatus onRunning() override
267+
{
268+
return BT::NodeStatus::RUNNING;
269+
}
270+
271+
void onHalted() override {
272+
std::cout << "Node halted\n";
273+
}
274+
};
275+
276+
TEST(Preconditions, Issue615_NoSkipWhenRunning_B)
277+
{
278+
static constexpr auto xml_text = R"(
279+
<root BTCPP_format="4">
280+
<BehaviorTree>
281+
<KeepRunning _skipIf="check==false"/>
282+
</BehaviorTree>
283+
</root>
284+
)";
285+
286+
BehaviorTreeFactory factory;
287+
factory.registerNodeType<KeepRunning>("KeepRunning");
288+
auto tree = factory.createTreeFromText(xml_text);
289+
290+
tree.rootBlackboard()->set("check", false);
291+
ASSERT_EQ( tree.tickOnce(), NodeStatus::SKIPPED );
292+
293+
// Should not be skipped anymore
294+
tree.rootBlackboard()->set("check", true);
295+
ASSERT_EQ( tree.tickOnce(), NodeStatus::RUNNING );
296+
297+
// skipIf should be ignored, because KeepRunning is RUNNING and not IDLE
298+
tree.rootBlackboard()->set("check", false);
299+
ASSERT_EQ( tree.tickOnce(), NodeStatus::RUNNING );
300+
}

0 commit comments

Comments
 (0)