Skip to content

Commit 53e1f15

Browse files
committed
ReactiveSequence and ReactiveFallback will behave more similarly to 3.8
1 parent 157873f commit 53e1f15

File tree

4 files changed

+73
-17
lines changed

4 files changed

+73
-17
lines changed

include/behaviortree_cpp/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/controls/reactive_sequence.h

Lines changed: 7 additions & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -36,10 +36,16 @@ 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+
*/
3943
static void EnableException(bool enable);
4044

4145
private:
42-
virtual BT::NodeStatus tick() override;
46+
BT::NodeStatus tick() override;
47+
48+
void halt() override;
4349

4450
int running_child_ = -1;
4551

src/controls/reactive_fallback.cpp

Lines changed: 35 additions & 10 deletions
Original file line numberDiff line numberDiff line change
@@ -14,11 +14,21 @@
1414

1515
namespace BT
1616
{
17-
NodeStatus ReactiveFallback::tick()
17+
18+
bool ReactiveFallback::throw_if_multiple_running = true;
19+
20+
void ReactiveFallback::EnableException(bool enable)
1821
{
19-
size_t failure_count = 0;
22+
ReactiveFallback::throw_if_multiple_running = enable;
23+
}
2024

25+
NodeStatus ReactiveFallback::tick()
26+
{
2127
bool all_skipped = true;
28+
if(status() == NodeStatus::IDLE)
29+
{
30+
running_child_ = -1;
31+
}
2232
setStatus(NodeStatus::RUNNING);
2333

2434
for (size_t index = 0; index < childrenCount(); index++)
@@ -32,19 +42,28 @@ NodeStatus ReactiveFallback::tick()
3242
switch (child_status)
3343
{
3444
case NodeStatus::RUNNING: {
35-
// reset the previous children, to make sure that they are in IDLE state
36-
// the next time we tick them
37-
for (size_t i = 0; i < index; i++)
45+
// reset the previous children, to make sure that they are
46+
// in IDLE state the next time we tick them
47+
for (size_t i = 0; i < childrenCount(); i++)
48+
{
49+
if(i != index)
50+
{
51+
haltChild(i);
52+
}
53+
}
54+
if(running_child_ == -1)
55+
{
56+
running_child_ = int(index);
57+
}
58+
else if(throw_if_multiple_running && running_child_ != int(index))
3859
{
39-
haltChild(i);
60+
throw LogicError("[ReactiveFallback]: only a single child can return RUNNING.\n"
61+
"This throw can be disabled with ReactiveFallback::EnableException(false)");
4062
}
4163
return NodeStatus::RUNNING;
4264
}
4365

44-
case NodeStatus::FAILURE: {
45-
failure_count++;
46-
}
47-
break;
66+
case NodeStatus::FAILURE: break;
4867

4968
case NodeStatus::SUCCESS: {
5069
resetChildren();
@@ -69,4 +88,10 @@ NodeStatus ReactiveFallback::tick()
6988
return all_skipped ? NodeStatus::SKIPPED : NodeStatus::FAILURE;
7089
}
7190

91+
void ReactiveFallback::halt()
92+
{
93+
running_child_ = -1;
94+
ControlNode::halt();
95+
}
96+
7297
} // namespace BT

src/controls/reactive_sequence.cpp

Lines changed: 19 additions & 5 deletions
Original file line numberDiff line numberDiff line change
@@ -25,6 +25,10 @@ void ReactiveSequence::EnableException(bool enable)
2525
NodeStatus ReactiveSequence::tick()
2626
{
2727
bool all_skipped = true;
28+
if(status() == NodeStatus::IDLE)
29+
{
30+
running_child_ = -1;
31+
}
2832
setStatus(NodeStatus::RUNNING);
2933

3034
for (size_t index = 0; index < childrenCount(); index++)
@@ -38,19 +42,23 @@ NodeStatus ReactiveSequence::tick()
3842
switch (child_status)
3943
{
4044
case NodeStatus::RUNNING: {
41-
// reset the previous children, to make sure that they are in IDLE state
42-
// the next time we tick them
43-
for (size_t i = 0; i < index; i++)
45+
// reset the previous children, to make sure that they are
46+
// in IDLE state the next time we tick them
47+
for (size_t i = 0; i < childrenCount(); i++)
4448
{
45-
haltChild(i);
49+
if(i != index)
50+
{
51+
haltChild(i);
52+
}
4653
}
4754
if(running_child_ == -1)
4855
{
4956
running_child_ = int(index);
5057
}
5158
else if(throw_if_multiple_running && running_child_ != int(index))
5259
{
53-
throw LogicError("[ReactiveSequence]: only a single child can return RUNNING");
60+
throw LogicError("[ReactiveSequence]: only a single child can return RUNNING.\n"
61+
"This throw can be disabled with ReactiveSequence::EnableException(false)");
5462
}
5563
return NodeStatus::RUNNING;
5664
}
@@ -80,4 +88,10 @@ NodeStatus ReactiveSequence::tick()
8088
return all_skipped ? NodeStatus::SKIPPED : NodeStatus::SUCCESS;
8189
}
8290

91+
void ReactiveSequence::halt()
92+
{
93+
running_child_ = -1;
94+
ControlNode::halt();
95+
}
96+
8397
} // namespace BT

0 commit comments

Comments
 (0)