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

Skip to content

Commit c66d25a

Browse files
committed
ActionNodeBase will be called only once by a ControlNode
1 parent 1278da4 commit c66d25a

File tree

5 files changed

+32
-19
lines changed

5 files changed

+32
-19
lines changed

gtest/gtest_sequence.cpp

Lines changed: 13 additions & 19 deletions
Original file line numberDiff line numberDiff line change
@@ -66,12 +66,15 @@ struct ComplexSequenceTest : testing::Test
6666
struct SequenceTripleActionTest : testing::Test
6767
{
6868
BT::SequenceNode root;
69+
BT::ConditionTestNode condition;
6970
BT::AsyncActionTest action_1;
7071
BT::SyncActionTest action_2;
7172
BT::AsyncActionTest action_3;
7273

73-
SequenceTripleActionTest() : root("root_sequence"), action_1("action_1"), action_2("action_2"), action_3("action_3")
74+
SequenceTripleActionTest() : root("root_sequence"), condition("condition"),
75+
action_1("action_1"), action_2("action_2"), action_3("action_3")
7476
{
77+
root.addChild(&condition);
7578
root.addChild(&action_1);
7679
root.addChild(&action_2);
7780
root.addChild(&action_3);
@@ -247,21 +250,7 @@ TEST_F(SequenceTripleActionTest, TripleAction)
247250

248251
action_1.setTime(3);
249252
action_3.setTime(3);
250-
// the sequence is supposed to finish in (200 ms * 3) = 600 ms
251-
252-
int count_1 = 0, count_2 = 0, count_3 = 0;
253-
254-
auto sub1 = action_1.subscribeToStatusChange([&](TimePoint, const TreeNode&, NodeStatus, NodeStatus status) {
255-
if (status == NodeStatus::SUCCESS) count_1++;
256-
});
257-
258-
auto sub2 = action_2.subscribeToStatusChange([&](TimePoint, const TreeNode&, NodeStatus, NodeStatus status) {
259-
if (status == NodeStatus::SUCCESS) count_2++;
260-
});
261-
262-
auto sub3 = action_3.subscribeToStatusChange([&](TimePoint, const TreeNode&, NodeStatus, NodeStatus status) {
263-
if (status == NodeStatus::SUCCESS) count_3++;
264-
});
253+
// the sequence is supposed to finish in (300 ms * 2) = 600 ms
265254

266255
// first tick
267256
NodeStatus state = root.executeTick();
@@ -279,9 +268,14 @@ TEST_F(SequenceTripleActionTest, TripleAction)
279268
}
280269

281270
ASSERT_EQ(NodeStatus::SUCCESS, state);
282-
ASSERT_TRUE(count_1 == 1);
283-
ASSERT_TRUE(count_2 == 1);
284-
ASSERT_TRUE(count_3 == 1);
271+
272+
// Condition is called many times
273+
ASSERT_NE(condition.tickCount(), 30);
274+
// all the actions are called only once
275+
ASSERT_EQ(action_1.tickCount(), 1);
276+
ASSERT_EQ(action_2.tickCount(), 1);
277+
ASSERT_EQ(action_3.tickCount(), 1);
278+
285279
ASSERT_EQ(NodeStatus::IDLE, action_1.status());
286280
ASSERT_EQ(NodeStatus::IDLE, action_2.status());
287281
ASSERT_EQ(NodeStatus::IDLE, action_3.status());

gtest/include/condition_test_node.h

Lines changed: 3 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -16,8 +16,11 @@ class ConditionTestNode : public ConditionNode
1616
// The method that is going to be executed by the thread
1717
virtual BT::NodeStatus tick() override;
1818

19+
int tickCount() const { return tick_count_; }
20+
1921
private:
2022
bool boolean_value_;
23+
int tick_count_;
2124
};
2225
}
2326

gtest/src/condition_test_node.cpp

Lines changed: 3 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -16,11 +16,14 @@
1616
BT::ConditionTestNode::ConditionTestNode(const std::string& name) : ConditionNode::ConditionNode(name)
1717
{
1818
boolean_value_ = true;
19+
tick_count_ = 0;
1920
}
2021

2122

2223
BT::NodeStatus BT::ConditionTestNode::tick()
2324
{
25+
tick_count_++;
26+
2427
// Condition checking and state update
2528
if (boolean_value_)
2629
{

include/behavior_tree_core/action_node.h

Lines changed: 2 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -26,6 +26,8 @@ class ActionNodeBase : public LeafNode
2626
ActionNodeBase(const std::string& name, const NodeParameters& parameters = NodeParameters());
2727
~ActionNodeBase() override = default;
2828

29+
virtual NodeStatus executeTick() override;
30+
2931
virtual NodeType type() const override final
3032
{
3133
return NodeType::ACTION;

src/action_node.cpp

Lines changed: 11 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -20,6 +20,17 @@ ActionNodeBase::ActionNodeBase(const std::string& name, const NodeParameters& pa
2020
{
2121
}
2222

23+
NodeStatus ActionNodeBase::executeTick()
24+
{
25+
NodeStatus prev_status = status();
26+
27+
if (prev_status == NodeStatus::IDLE || prev_status == NodeStatus::RUNNING)
28+
{
29+
setStatus( tick() );
30+
}
31+
return status();
32+
}
33+
2334
//-------------------------------------------------------
2435

2536
SimpleActionNode::SimpleActionNode(const std::string& name, SimpleActionNode::TickFunctor tick_functor)

0 commit comments

Comments
 (0)