13 #include <gtest/gtest.h> 47 : root(
"root_sequence")
48 , action_1(
"action_1")
49 , condition_1(
"condition_1")
50 , condition_2(
"condition_2")
51 , seq_conditions(
"sequence_conditions")
55 seq_conditions.
addChild(&condition_1);
56 seq_conditions.
addChild(&condition_2);
75 : root(
"root_sequence")
76 , condition(
"condition")
77 , action_1(
"action_1")
78 , action_2(
"action_2")
79 , action_3(
"action_3")
104 : root(
"root_sequence")
105 , action_1(
"action_1")
106 , action_2(
"action_2")
107 , seq_1(
"sequence_1")
108 , seq_2(
"sequence_2")
109 , condition_1(
"condition_1")
110 , condition_2(
"condition_2")
160 : root(
"root_sequence")
161 , action_1(
"action_1")
162 , action_2(
"action_2")
163 , condition_1(
"condition_1")
164 , condition_2(
"condition_2")
165 , seq_conditions(
"sequence_conditions")
166 , seq_actions(
"sequence_actions")
170 seq_conditions.
addChild(&condition_1);
171 seq_conditions.
addChild(&condition_2);
195 : root(
"root_parallel", 4)
196 , action_1(
"action_1")
197 , condition_1(
"condition_1")
198 , action_2(
"action_2")
199 , condition_2(
"condition_2")
216 std::cout <<
"Ticking the root node !" << std::endl << std::endl;
221 ASSERT_EQ(NodeStatus::RUNNING, state);
230 ASSERT_EQ(NodeStatus::FAILURE, state);
239 ASSERT_EQ(NodeStatus::RUNNING, state);
240 ASSERT_EQ(NodeStatus::SUCCESS, seq_conditions.status());
241 ASSERT_EQ(NodeStatus::IDLE, condition_1.status());
242 ASSERT_EQ(NodeStatus::IDLE, condition_1.status());
243 ASSERT_EQ(NodeStatus::RUNNING, action_1.status());
249 using namespace std::chrono;
250 const auto timeout = system_clock::now() + milliseconds(650);
259 ASSERT_EQ(NodeStatus::RUNNING, state);
260 ASSERT_EQ(NodeStatus::RUNNING, action_1.status());
261 ASSERT_EQ(NodeStatus::IDLE, action_2.status());
262 ASSERT_EQ(NodeStatus::IDLE, action_3.status());
265 while (state != NodeStatus::SUCCESS && system_clock::now() < timeout)
267 std::this_thread::sleep_for(milliseconds(20));
271 ASSERT_EQ(NodeStatus::SUCCESS, state);
276 ASSERT_EQ(action_1.tickCount(), 1);
277 ASSERT_EQ(action_2.tickCount(), 1);
278 ASSERT_EQ(action_3.tickCount(), 1);
280 ASSERT_EQ(NodeStatus::IDLE, action_1.status());
281 ASSERT_EQ(NodeStatus::IDLE, action_2.status());
282 ASSERT_EQ(NodeStatus::IDLE, action_3.status());
283 ASSERT_TRUE(system_clock::now() < timeout);
292 ASSERT_EQ(NodeStatus::RUNNING, state);
293 ASSERT_EQ(NodeStatus::RUNNING, seq_1.status());
294 ASSERT_EQ(NodeStatus::SUCCESS, condition_1.status());
295 ASSERT_EQ(NodeStatus::RUNNING, action_1.status());
296 ASSERT_EQ(NodeStatus::IDLE, seq_2.status());
297 ASSERT_EQ(NodeStatus::IDLE, condition_2.status());
298 ASSERT_EQ(NodeStatus::IDLE, action_2.status());
300 std::this_thread::sleep_for(std::chrono::milliseconds(500));
303 ASSERT_EQ(NodeStatus::RUNNING, state);
304 ASSERT_EQ(NodeStatus::SUCCESS, seq_1.status());
305 ASSERT_EQ(NodeStatus::IDLE, condition_1.status());
306 ASSERT_EQ(NodeStatus::IDLE, action_1.status());
307 ASSERT_EQ(NodeStatus::RUNNING, seq_2.status());
308 ASSERT_EQ(NodeStatus::SUCCESS, condition_2.status());
309 ASSERT_EQ(NodeStatus::RUNNING, action_2.status());
318 condition_1.setBoolean(
false);
322 ASSERT_EQ(NodeStatus::FAILURE, state);
323 ASSERT_EQ(NodeStatus::IDLE, seq_conditions.status());
324 ASSERT_EQ(NodeStatus::IDLE, condition_1.status());
325 ASSERT_EQ(NodeStatus::IDLE, condition_2.status());
326 ASSERT_EQ(NodeStatus::IDLE, action_1.status());
333 condition_2.setBoolean(
false);
337 ASSERT_EQ(NodeStatus::FAILURE, state);
338 ASSERT_EQ(NodeStatus::IDLE, seq_conditions.status());
339 ASSERT_EQ(NodeStatus::IDLE, condition_1.status());
340 ASSERT_EQ(NodeStatus::IDLE, condition_2.status());
341 ASSERT_EQ(NodeStatus::IDLE, action_1.status());
347 std::this_thread::sleep_for(std::chrono::milliseconds(100));
349 ASSERT_EQ(NodeStatus::RUNNING, state);
358 ASSERT_EQ(NodeStatus::RUNNING, state);
365 ASSERT_EQ(NodeStatus::RUNNING, state);
374 ASSERT_EQ(NodeStatus::RUNNING, state);
375 ASSERT_EQ(NodeStatus::SUCCESS, seq_conditions.status());
376 ASSERT_EQ(NodeStatus::IDLE, condition_1.status());
377 ASSERT_EQ(NodeStatus::IDLE, condition_2.status());
378 ASSERT_EQ(NodeStatus::RUNNING, seq_actions.status());
379 ASSERT_EQ(NodeStatus::RUNNING, action_1.status());
380 ASSERT_EQ(NodeStatus::IDLE, action_2.status());
387 condition_1.setBoolean(
false);
391 ASSERT_EQ(NodeStatus::RUNNING, state);
392 ASSERT_EQ(NodeStatus::SUCCESS, seq_conditions.status());
393 ASSERT_EQ(NodeStatus::IDLE, condition_1.status());
394 ASSERT_EQ(NodeStatus::IDLE, condition_2.status());
395 ASSERT_EQ(NodeStatus::RUNNING, seq_actions.status());
396 ASSERT_EQ(NodeStatus::RUNNING, action_1.status());
397 ASSERT_EQ(NodeStatus::IDLE, action_2.status());
404 condition_2.setBoolean(
false);
408 ASSERT_EQ(NodeStatus::RUNNING, state);
409 ASSERT_EQ(NodeStatus::SUCCESS, seq_conditions.status());
410 ASSERT_EQ(NodeStatus::IDLE, condition_1.status());
411 ASSERT_EQ(NodeStatus::IDLE, condition_2.status());
412 ASSERT_EQ(NodeStatus::RUNNING, seq_actions.status());
413 ASSERT_EQ(NodeStatus::RUNNING, action_1.status());
414 ASSERT_EQ(NodeStatus::IDLE, action_2.status());
421 condition_2.setBoolean(
false);
426 ASSERT_EQ(NodeStatus::SUCCESS, seq_conditions.status());
427 ASSERT_EQ(NodeStatus::IDLE, condition_1.status());
428 ASSERT_EQ(NodeStatus::IDLE, condition_2.status());
429 ASSERT_EQ(NodeStatus::RUNNING, seq_actions.status());
430 ASSERT_EQ(NodeStatus::RUNNING, action_1.status());
431 ASSERT_EQ(NodeStatus::IDLE, action_2.status());
433 std::this_thread::sleep_for(std::chrono::milliseconds(400));
436 ASSERT_EQ(NodeStatus::SUCCESS, seq_conditions.status());
437 ASSERT_EQ(NodeStatus::IDLE, condition_1.status());
438 ASSERT_EQ(NodeStatus::IDLE, condition_2.status());
439 ASSERT_EQ(NodeStatus::RUNNING, seq_actions.status());
440 ASSERT_EQ(NodeStatus::SUCCESS, action_1.status());
441 ASSERT_EQ(NodeStatus::RUNNING, action_2.status());
443 std::this_thread::sleep_for(std::chrono::milliseconds(400));
446 ASSERT_EQ(NodeStatus::SUCCESS,
root.
status());
447 ASSERT_EQ(NodeStatus::IDLE, seq_conditions.status());
448 ASSERT_EQ(NodeStatus::IDLE, condition_1.status());
449 ASSERT_EQ(NodeStatus::IDLE, condition_2.status());
450 ASSERT_EQ(NodeStatus::IDLE, seq_actions.status());
451 ASSERT_EQ(NodeStatus::IDLE, action_1.status());
452 ASSERT_EQ(NodeStatus::IDLE, action_2.status());
~SequenceTripleActionTest()
BT::ConditionTestNode condition_1
BT::AsyncActionTest action_2
The SequenceStarNode is used to execute a sequence of children. If any child returns RUNNING...
BT::ConditionTestNode condition_1
SequenceTripleActionTest()
BT::ConditionTestNode condition_2
BT::SequenceStarNode seq_conditions
BT::ConditionTestNode condition_1
TEST_F(SimpleSequenceTest, ConditionTrue)
BT::SequenceStarNode root
BT::AsyncActionTest action_1
~ComplexSequenceWithMemoryTest()
SimpleSequenceWithMemoryTest()
void setBoolean(bool boolean_value)
BT::ConditionTestNode condition_2
BT::AsyncActionTest action
BT::AsyncActionTest action
ComplexSequence2ActionsTest()
BT::AsyncActionTest action_1
void haltAllActions(TreeNode *root_node)
BT::ConditionTestNode condition
BT::SequenceStarNode seq_actions
BT::SyncActionTest action_2
BT::ConditionTestNode condition_2
BT::AsyncActionTest action_3
void addChild(TreeNode *child)
BT::SequenceNode seq_conditions
BT::ConditionTestNode condition
BT::ConditionTestNode condition
NodeStatus status() const
BT::AsyncActionTest action_1
BT::AsyncActionTest action_2
~ComplexSequence2ActionsTest()
ComplexSequenceWithMemoryTest()
BT::SequenceStarNode root
virtual BT::NodeStatus executeTick()
The method that will be executed to invoke tick(); and setStatus();.
~SimpleSequenceWithMemoryTest()
The SequenceNode is used to execute a sequence of children. If any child returns RUNNING, previous children will be ticked again.
BT::AsyncActionTest action_1