Skip to content

Commit db25cfb

Browse files
afrixsfacontidavideMatej Vargovcik
authored
Fixed #810 - halting of subsequent nodes in ReactiveSequence/Fallback (#817)
* ReactiveSequence and ReactiveFallback will behave more similarly to 3.8 * Reactive Sequence/Fallback defaulting to allow multiple async nodes --------- Co-authored-by: Davide Faconti <[email protected]> Co-authored-by: Matej Vargovcik <[email protected]>
1 parent 95210b0 commit db25cfb

File tree

4 files changed

+95
-11
lines changed

4 files changed

+95
-11
lines changed

include/behaviortree_cpp_v3/controls/reactive_fallback.h

Lines changed: 12 additions & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -36,8 +36,19 @@ class ReactiveFallback : public ControlNode
3636
ReactiveFallback(const std::string& name) : ControlNode(name, {})
3737
{}
3838

39+
/** A ReactiveFallback is not supposed to have more than a single
40+
* anychronous node; if it does an exception is thrown.
41+
* You can disabled that check, if you know what you are doing.
42+
*/
43+
static void EnableException(bool enable);
44+
3945
private:
40-
virtual BT::NodeStatus tick() override;
46+
BT::NodeStatus tick() override;
47+
48+
void halt() override;
49+
50+
int running_child_ = -1;
51+
static bool throw_if_multiple_running;
4152
};
4253

4354
} // namespace BT

include/behaviortree_cpp_v3/controls/reactive_sequence.h

Lines changed: 13 additions & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -36,8 +36,20 @@ class ReactiveSequence : public ControlNode
3636
ReactiveSequence(const std::string& name) : ControlNode(name, {})
3737
{}
3838

39+
/** A ReactiveSequence is not supposed to have more than a single
40+
* anychronous node; if it does an exception is thrown.
41+
* You can disabled that check, if you know what you are doing.
42+
*/
43+
static void EnableException(bool enable);
44+
3945
private:
40-
virtual BT::NodeStatus tick() override;
46+
BT::NodeStatus tick() override;
47+
48+
void halt() override;
49+
50+
int running_child_ = -1;
51+
52+
static bool throw_if_multiple_running;
4153
};
4254

4355
} // namespace BT

src/controls/reactive_fallback.cpp

Lines changed: 35 additions & 5 deletions
Original file line numberDiff line numberDiff line change
@@ -14,9 +14,22 @@
1414

1515
namespace BT
1616
{
17+
18+
bool ReactiveFallback::throw_if_multiple_running = false;
19+
20+
void ReactiveFallback::EnableException(bool enable)
21+
{
22+
ReactiveFallback::throw_if_multiple_running = enable;
23+
}
24+
1725
NodeStatus ReactiveFallback::tick()
1826
{
1927
size_t failure_count = 0;
28+
if(status() == NodeStatus::IDLE)
29+
{
30+
running_child_ = -1;
31+
}
32+
setStatus(NodeStatus::RUNNING);
2033

2134
for (size_t index = 0; index < childrenCount(); index++)
2235
{
@@ -26,12 +39,23 @@ NodeStatus ReactiveFallback::tick()
2639
switch (child_status)
2740
{
2841
case NodeStatus::RUNNING: {
29-
30-
// reset the previous children, to make sure that they are in IDLE state
31-
// the next time we tick them
32-
for (size_t i = 0; i < index; i++)
42+
// reset the previous children, to make sure that they are
43+
// in IDLE state the next time we tick them
44+
for (size_t i = 0; i < childrenCount(); i++)
3345
{
34-
haltChild(i);
46+
if(i != index)
47+
{
48+
haltChild(i);
49+
}
50+
}
51+
if(running_child_ == -1)
52+
{
53+
running_child_ = int(index);
54+
}
55+
else if(throw_if_multiple_running && running_child_ != int(index))
56+
{
57+
throw LogicError("[ReactiveFallback]: only a single child can return RUNNING.\n"
58+
"This throw can be disabled with ReactiveFallback::EnableException(false)");
3559
}
3660
return NodeStatus::RUNNING;
3761
}
@@ -61,4 +85,10 @@ NodeStatus ReactiveFallback::tick()
6185
return NodeStatus::RUNNING;
6286
}
6387

88+
void ReactiveFallback::halt()
89+
{
90+
running_child_ = -1;
91+
ControlNode::halt();
92+
}
93+
6494
} // namespace BT

src/controls/reactive_sequence.cpp

Lines changed: 35 additions & 4 deletions
Original file line numberDiff line numberDiff line change
@@ -14,9 +14,22 @@
1414

1515
namespace BT
1616
{
17+
18+
bool ReactiveSequence::throw_if_multiple_running = false;
19+
20+
void ReactiveSequence::EnableException(bool enable)
21+
{
22+
ReactiveSequence::throw_if_multiple_running = enable;
23+
}
24+
1725
NodeStatus ReactiveSequence::tick()
1826
{
1927
size_t success_count = 0;
28+
if(status() == NodeStatus::IDLE)
29+
{
30+
running_child_ = -1;
31+
}
32+
setStatus(NodeStatus::RUNNING);
2033

2134
for (size_t index = 0; index < childrenCount(); index++)
2235
{
@@ -26,11 +39,23 @@ NodeStatus ReactiveSequence::tick()
2639
switch (child_status)
2740
{
2841
case NodeStatus::RUNNING: {
29-
// reset the previous children, to make sure that they are in IDLE state
30-
// the next time we tick them
31-
for (size_t i = 0; i < index; i++)
42+
// reset the previous children, to make sure that they are
43+
// in IDLE state the next time we tick them
44+
for (size_t i = 0; i < childrenCount(); i++)
3245
{
33-
haltChild(i);
46+
if(i != index)
47+
{
48+
haltChild(i);
49+
}
50+
}
51+
if(running_child_ == -1)
52+
{
53+
running_child_ = int(index);
54+
}
55+
else if(throw_if_multiple_running && running_child_ != int(index))
56+
{
57+
throw LogicError("[ReactiveSequence]: only a single child can return RUNNING.\n"
58+
"This throw can be disabled with ReactiveSequence::EnableException(false)");
3459
}
3560
return NodeStatus::RUNNING;
3661
}
@@ -59,4 +84,10 @@ NodeStatus ReactiveSequence::tick()
5984
return NodeStatus::RUNNING;
6085
}
6186

87+
void ReactiveSequence::halt()
88+
{
89+
running_child_ = -1;
90+
ControlNode::halt();
91+
}
92+
6293
} // namespace BT

0 commit comments

Comments
 (0)