13 #include <gtest/gtest.h> 19 using std::chrono::milliseconds;
31 root(
"root_parallel", 4),
32 action_1(
"action_1", milliseconds(100)),
33 condition_1(
"condition_1"),
34 action_2(
"action_2", milliseconds(300)),
35 condition_2(
"condition_2")
62 parallel_root(
"root", 2),
63 parallel_left(
"par1", 3),
64 parallel_right(
"par2", 1),
65 action_L1(
"action_1", milliseconds(100)),
66 condition_L1(
"condition_1"),
67 action_L2(
"action_2", milliseconds(200)),
68 condition_L2(
"condition_2"),
69 action_R(
"action_3", milliseconds(400)),
70 condition_R(
"condition_3")
72 parallel_root.
addChild(¶llel_left);
74 parallel_left.
addChild(&condition_L1);
76 parallel_left.
addChild(&condition_L2);
79 parallel_root.
addChild(¶llel_right);
81 parallel_right.
addChild(&condition_R);
99 ASSERT_EQ(NodeStatus::RUNNING, state);
101 std::this_thread::sleep_for(milliseconds(200));
108 ASSERT_EQ(NodeStatus::RUNNING, state);
110 std::this_thread::sleep_for(milliseconds(200));
117 ASSERT_EQ(NodeStatus::SUCCESS, state);
132 ASSERT_EQ(NodeStatus::RUNNING, state);
134 std::this_thread::sleep_for(milliseconds(150));
142 ASSERT_EQ(NodeStatus::SUCCESS, state);
157 ASSERT_EQ(NodeStatus::RUNNING, state);
159 std::this_thread::sleep_for(milliseconds(150));
167 ASSERT_EQ(NodeStatus::SUCCESS, state);
182 ASSERT_EQ(NodeStatus::RUNNING, state);
184 std::this_thread::sleep_for(milliseconds(150));
191 ASSERT_EQ(NodeStatus::RUNNING, state);
193 std::this_thread::sleep_for(milliseconds(650));
200 ASSERT_EQ(NodeStatus::SUCCESS, state);
215 ASSERT_EQ(NodeStatus::RUNNING, state);
217 std::this_thread::sleep_for(milliseconds(250));
219 ASSERT_EQ(NodeStatus::FAILURE, state);
231 ASSERT_EQ(NodeStatus::SUCCESS, state);
238 ASSERT_EQ(NodeStatus::RUNNING, parallel_left.status());
239 ASSERT_EQ(NodeStatus::SUCCESS, condition_L1.status());
240 ASSERT_EQ(NodeStatus::SUCCESS, condition_L2.status());
241 ASSERT_EQ(NodeStatus::RUNNING, action_L1.status());
242 ASSERT_EQ(NodeStatus::RUNNING, action_L2.status());
244 ASSERT_EQ(NodeStatus::SUCCESS, parallel_right.status());
245 ASSERT_EQ(NodeStatus::IDLE, condition_R.status());
246 ASSERT_EQ(NodeStatus::IDLE, action_R.status());
248 ASSERT_EQ(NodeStatus::RUNNING, state);
250 std::this_thread::sleep_for(milliseconds(200));
251 state = parallel_root.executeTick();
253 ASSERT_EQ(NodeStatus::IDLE, parallel_left.status());
254 ASSERT_EQ(NodeStatus::IDLE, condition_L1.status());
255 ASSERT_EQ(NodeStatus::IDLE, condition_L2.status());
256 ASSERT_EQ(NodeStatus::IDLE, action_L1.status());
257 ASSERT_EQ(NodeStatus::IDLE, action_L2.status());
259 ASSERT_EQ(NodeStatus::IDLE, parallel_right.status());
260 ASSERT_EQ(NodeStatus::IDLE, condition_R.status());
261 ASSERT_EQ(NodeStatus::IDLE, action_R.status());
263 ASSERT_EQ(NodeStatus::SUCCESS, state);
268 parallel_left.setFailureThreshold(3);
269 parallel_left.setSuccessThreshold(3);
270 condition_L1.setExpectedResult(NodeStatus::FAILURE);
271 condition_L2.setExpectedResult(NodeStatus::FAILURE);
277 ASSERT_EQ(NodeStatus::IDLE, parallel_left.status());
278 ASSERT_EQ(NodeStatus::IDLE, condition_L1.status());
279 ASSERT_EQ(NodeStatus::IDLE, condition_L2.status());
280 ASSERT_EQ(NodeStatus::IDLE, action_L1.status());
281 ASSERT_EQ(NodeStatus::IDLE, action_L2.status());
283 ASSERT_EQ(NodeStatus::IDLE, parallel_right.status());
284 ASSERT_EQ(NodeStatus::IDLE, condition_R.status());
285 ASSERT_EQ(NodeStatus::IDLE, action_R.status());
287 ASSERT_EQ(NodeStatus::FAILURE, state);
292 condition_R.setExpectedResult(NodeStatus::FAILURE);
298 ASSERT_EQ(NodeStatus::IDLE, parallel_left.status());
299 ASSERT_EQ(NodeStatus::IDLE, condition_L1.status());
300 ASSERT_EQ(NodeStatus::IDLE, condition_L2.status());
301 ASSERT_EQ(NodeStatus::IDLE, action_L1.status());
302 ASSERT_EQ(NodeStatus::IDLE, action_L2.status());
304 ASSERT_EQ(NodeStatus::IDLE, parallel_right.status());
305 ASSERT_EQ(NodeStatus::IDLE, condition_R.status());
306 ASSERT_EQ(NodeStatus::IDLE, action_R.status());
308 ASSERT_EQ(NodeStatus::FAILURE, state);
313 parallel_right.setFailureThreshold(2);
314 condition_R.setExpectedResult(NodeStatus::FAILURE);
319 ASSERT_EQ(NodeStatus::RUNNING, parallel_left.status());
320 ASSERT_EQ(NodeStatus::SUCCESS, condition_L1.status());
321 ASSERT_EQ(NodeStatus::SUCCESS, condition_L2.status());
322 ASSERT_EQ(NodeStatus::RUNNING, action_L1.status());
323 ASSERT_EQ(NodeStatus::RUNNING, action_L2.status());
325 ASSERT_EQ(NodeStatus::RUNNING, parallel_right.status());
326 ASSERT_EQ(NodeStatus::FAILURE, condition_R.status());
327 ASSERT_EQ(NodeStatus::RUNNING, action_R.status());
329 ASSERT_EQ(NodeStatus::RUNNING, state);
332 std::this_thread::sleep_for(milliseconds(500));
333 state = parallel_root.executeTick();
335 ASSERT_EQ(NodeStatus::IDLE, parallel_left.status());
336 ASSERT_EQ(NodeStatus::IDLE, condition_L1.status());
337 ASSERT_EQ(NodeStatus::IDLE, condition_L2.status());
338 ASSERT_EQ(NodeStatus::IDLE, action_L1.status());
339 ASSERT_EQ(NodeStatus::IDLE, action_L2.status());
341 ASSERT_EQ(NodeStatus::IDLE, parallel_right.status());
342 ASSERT_EQ(NodeStatus::IDLE, condition_R.status());
343 ASSERT_EQ(NodeStatus::IDLE, action_R.status());
345 ASSERT_EQ(NodeStatus::SUCCESS, state);
350 condition_R.setExpectedResult(NodeStatus::FAILURE);
352 parallel_right.setFailureThreshold(2);
353 parallel_left.setSuccessThreshold(4);
356 std::this_thread::sleep_for(milliseconds(300));
359 ASSERT_EQ(NodeStatus::RUNNING, parallel_left.status());
360 ASSERT_EQ(NodeStatus::SUCCESS, condition_L1.status());
361 ASSERT_EQ(NodeStatus::SUCCESS, condition_L2.status());
362 ASSERT_EQ(NodeStatus::SUCCESS, action_L1.status());
363 ASSERT_EQ(NodeStatus::SUCCESS, action_L2.status());
365 ASSERT_EQ(NodeStatus::RUNNING, parallel_right.status());
368 state = parallel_root.executeTick();
370 ASSERT_EQ(NodeStatus::SUCCESS, parallel_left.status());
371 ASSERT_EQ(NodeStatus::IDLE, condition_L1.status());
372 ASSERT_EQ(NodeStatus::IDLE, condition_L2.status());
373 ASSERT_EQ(NodeStatus::IDLE, action_L1.status());
374 ASSERT_EQ(NodeStatus::IDLE, action_L2.status());
376 ASSERT_EQ(NodeStatus::RUNNING, parallel_right.status());
377 ASSERT_EQ(NodeStatus::RUNNING, action_R.status());
379 ASSERT_EQ(NodeStatus::RUNNING, state);
382 std::this_thread::sleep_for(milliseconds(300));
383 state = parallel_root.executeTick();
385 ASSERT_EQ(NodeStatus::IDLE, parallel_left.status());
386 ASSERT_EQ(NodeStatus::IDLE, action_L1.status());
388 ASSERT_EQ(NodeStatus::IDLE, parallel_right.status());
389 ASSERT_EQ(NodeStatus::IDLE, action_R.status());
391 ASSERT_EQ(NodeStatus::SUCCESS, state);
BT::AsyncActionTest action_L2
NodeStatus status() const
BT::ConditionTestNode condition_L2
BT::ConditionTestNode condition_2
BT::ConditionTestNode condition_R
BT::AsyncActionTest action_L1
void setExpectedResult(NodeStatus res)
BT::ParallelNode parallel_right
void setSuccessThreshold(int threshold_M)
BT::ParallelNode parallel_left
BT::AsyncActionTest action_R
void setTime(BT::Duration time)
BT::ConditionTestNode condition_L1
void addChild(TreeNode *child)
The method used to add nodes to the children vector.
BT::AsyncActionTest action_1
void setFailureThreshold(int threshold_M)
BT::ParallelNode parallel_root
TEST_F(SimpleParallelTest, ConditionsTrue)
The ParallelNode execute all its children concurrently, but not in separate threads! ...
void setExpectedResult(NodeStatus res)
virtual BT::NodeStatus executeTick()
The method that should be used to invoke tick() and setStatus();.
BT::ConditionTestNode condition_1
BT::AsyncActionTest action_2