13 #include <gtest/gtest.h>
20 using std::chrono::milliseconds;
49 ,
action_1(
"action_1", milliseconds(100))
74 :
root(
"root_sequence")
76 ,
action_1(
"action_1", milliseconds(100))
78 ,
action_3(
"action_3", milliseconds(100))
101 :
root(
"root_sequence")
102 ,
action_1(
"action_1", milliseconds(100))
103 ,
action_2(
"action_2", milliseconds(100))
104 ,
seq_1(
"sequence_1")
105 ,
seq_2(
"sequence_2")
154 :
root(
"root_sequence")
155 ,
action_1(
"action_1", milliseconds(100))
156 ,
action_2(
"action_2", milliseconds(100))
187 :
root(
"root_parallel")
188 ,
action_1(
"action_1", milliseconds(100))
190 ,
action_2(
"action_2", milliseconds(100))
207 std::cout <<
"Ticking the root node !" << std::endl << std::endl;
211 ASSERT_EQ(NodeStatus::RUNNING, action.status());
212 ASSERT_EQ(NodeStatus::RUNNING, state);
217 condition.setExpectedResult(NodeStatus::FAILURE);
220 state = root.executeTick();
221 ASSERT_EQ(NodeStatus::FAILURE, state);
222 ASSERT_EQ(NodeStatus::IDLE, condition.status());
223 ASSERT_EQ(NodeStatus::IDLE, action.status());
230 ASSERT_EQ(NodeStatus::RUNNING, state);
232 ASSERT_EQ(NodeStatus::IDLE, seq_conditions.status());
233 ASSERT_EQ(NodeStatus::IDLE, condition_1.status());
234 ASSERT_EQ(NodeStatus::IDLE, condition_2.status());
235 ASSERT_EQ(NodeStatus::RUNNING, action_1.status());
241 using namespace std::chrono;
244 const int margin_msec = 60;
246 const int margin_msec = 20;
249 const auto timeout = system_clock::now() + milliseconds(600 + margin_msec);
251 action_1.setTime(milliseconds(300));
252 action_3.setTime(milliseconds(300));
266 std::this_thread::sleep_for(milliseconds(1));
267 state = root.executeTick();
273 ASSERT_EQ(condition.tickCount(), 1);
275 ASSERT_EQ(action_1.tickCount(), 1);
276 ASSERT_EQ(action_2.tickCount(), 1);
277 ASSERT_EQ(action_3.tickCount(), 1);
282 ASSERT_TRUE(system_clock::now() < timeout);
289 state = root.executeTick();
299 std::this_thread::sleep_for(milliseconds(300));
300 state = root.executeTick();
310 state = root.executeTick();
319 state = root.executeTick();
334 state = root.executeTick();
346 std::this_thread::sleep_for(milliseconds(50));
362 state = root.executeTick();
387 state = root.executeTick();
399 TEST(SequenceWithMemoryTest, Issue_636)
403 <root BTCPP_format="4" main_tree_to_execute="MainTree" >
405 <BehaviorTree ID="MainTree">
407 <Script code = " var := 0 " />
409 <ScriptCondition code = "var+=1; var >= 5" />
412 </SequenceWithMemory>
418 std::array<int, 3> counters;
428 res = tree.tickOnce();
432 ASSERT_EQ(1, counters[0]);
433 ASSERT_EQ(1, counters[1]);
434 ASSERT_EQ(1, counters[2]);
436 ASSERT_EQ(5, tick_count);