14 #include <gtest/gtest.h>
22 using std::chrono::milliseconds;
34 :
root(
"root_parallel")
35 ,
action_1(
"action_1", milliseconds(100))
37 ,
action_2(
"action_2", milliseconds(300))
68 ,
action_L1(
"action_1", milliseconds(100))
70 ,
action_L2(
"action_2", milliseconds(200))
72 ,
action_R(
"action_3", milliseconds(400))
101 ASSERT_EQ(NodeStatus::SUCCESS, condition_1.status());
102 ASSERT_EQ(NodeStatus::SUCCESS, condition_2.status());
103 ASSERT_EQ(NodeStatus::RUNNING, action_1.status());
104 ASSERT_EQ(NodeStatus::RUNNING, action_2.status());
105 ASSERT_EQ(NodeStatus::RUNNING, state);
107 std::this_thread::sleep_for(milliseconds(200));
108 state = root.executeTick();
110 ASSERT_EQ(NodeStatus::SUCCESS, condition_1.status());
111 ASSERT_EQ(NodeStatus::SUCCESS, condition_2.status());
112 ASSERT_EQ(NodeStatus::SUCCESS, action_1.status());
113 ASSERT_EQ(NodeStatus::RUNNING, action_2.status());
114 ASSERT_EQ(NodeStatus::RUNNING, state);
116 std::this_thread::sleep_for(milliseconds(200));
117 state = root.executeTick();
119 ASSERT_EQ(NodeStatus::IDLE, condition_1.status());
120 ASSERT_EQ(NodeStatus::IDLE, condition_2.status());
121 ASSERT_EQ(NodeStatus::IDLE, action_1.status());
122 ASSERT_EQ(NodeStatus::IDLE, action_2.status());
123 ASSERT_EQ(NodeStatus::SUCCESS, state);
128 root.setSuccessThreshold(3);
129 action_1.setTime(milliseconds(100));
130 action_2.setTime(milliseconds(500));
134 ASSERT_EQ(NodeStatus::SUCCESS, condition_1.status());
135 ASSERT_EQ(NodeStatus::SUCCESS, condition_2.status());
136 ASSERT_EQ(NodeStatus::RUNNING, action_1.status());
137 ASSERT_EQ(NodeStatus::RUNNING, action_2.status());
138 ASSERT_EQ(NodeStatus::RUNNING, state);
140 std::this_thread::sleep_for(milliseconds(150));
141 state = root.executeTick();
144 ASSERT_EQ(NodeStatus::IDLE, condition_1.status());
145 ASSERT_EQ(NodeStatus::IDLE, condition_2.status());
146 ASSERT_EQ(NodeStatus::IDLE, action_1.status());
147 ASSERT_EQ(NodeStatus::IDLE, action_2.status());
148 ASSERT_EQ(NodeStatus::SUCCESS, state);
153 root.setSuccessThreshold(-2);
154 action_1.setTime(milliseconds(100));
155 action_2.setTime(milliseconds(500));
159 ASSERT_EQ(NodeStatus::SUCCESS, condition_1.status());
160 ASSERT_EQ(NodeStatus::SUCCESS, condition_2.status());
161 ASSERT_EQ(NodeStatus::RUNNING, action_1.status());
162 ASSERT_EQ(NodeStatus::RUNNING, action_2.status());
163 ASSERT_EQ(NodeStatus::RUNNING, state);
165 std::this_thread::sleep_for(milliseconds(150));
166 state = root.executeTick();
169 ASSERT_EQ(NodeStatus::IDLE, condition_1.status());
170 ASSERT_EQ(NodeStatus::IDLE, condition_2.status());
171 ASSERT_EQ(NodeStatus::IDLE, action_1.status());
172 ASSERT_EQ(NodeStatus::IDLE, action_2.status());
173 ASSERT_EQ(NodeStatus::SUCCESS, state);
178 root.setSuccessThreshold(-1);
179 action_1.setTime(milliseconds(100));
180 action_2.setTime(milliseconds(500));
184 ASSERT_EQ(NodeStatus::SUCCESS, condition_1.status());
185 ASSERT_EQ(NodeStatus::SUCCESS, condition_2.status());
186 ASSERT_EQ(NodeStatus::RUNNING, action_1.status());
187 ASSERT_EQ(NodeStatus::RUNNING, action_2.status());
188 ASSERT_EQ(NodeStatus::RUNNING, state);
190 std::this_thread::sleep_for(milliseconds(150));
191 state = root.executeTick();
193 ASSERT_EQ(NodeStatus::SUCCESS, condition_1.status());
194 ASSERT_EQ(NodeStatus::SUCCESS, condition_2.status());
195 ASSERT_EQ(NodeStatus::SUCCESS, action_1.status());
196 ASSERT_EQ(NodeStatus::RUNNING, action_2.status());
197 ASSERT_EQ(NodeStatus::RUNNING, state);
199 std::this_thread::sleep_for(milliseconds(650));
200 state = root.executeTick();
202 ASSERT_EQ(NodeStatus::IDLE, condition_1.status());
203 ASSERT_EQ(NodeStatus::IDLE, condition_2.status());
204 ASSERT_EQ(NodeStatus::IDLE, action_1.status());
205 ASSERT_EQ(NodeStatus::IDLE, action_2.status());
206 ASSERT_EQ(NodeStatus::SUCCESS, state);
211 root.setSuccessThreshold(1);
212 root.setFailureThreshold(-1);
213 action_1.setTime(milliseconds(100));
214 action_1.setExpectedResult(NodeStatus::FAILURE);
215 condition_1.setExpectedResult(NodeStatus::FAILURE);
216 action_2.setTime(milliseconds(200));
217 condition_2.setExpectedResult(NodeStatus::FAILURE);
218 action_2.setExpectedResult(NodeStatus::FAILURE);
221 ASSERT_EQ(NodeStatus::RUNNING, state);
223 std::this_thread::sleep_for(milliseconds(250));
224 state = root.executeTick();
225 ASSERT_EQ(NodeStatus::FAILURE, state);
230 root.setSuccessThreshold(2);
233 ASSERT_EQ(NodeStatus::IDLE, condition_1.status());
234 ASSERT_EQ(NodeStatus::IDLE, condition_2.status());
235 ASSERT_EQ(NodeStatus::IDLE, action_1.status());
236 ASSERT_EQ(NodeStatus::IDLE, action_2.status());
237 ASSERT_EQ(NodeStatus::SUCCESS, state);
244 ASSERT_EQ(NodeStatus::RUNNING, parallel_left.status());
245 ASSERT_EQ(NodeStatus::SUCCESS, condition_L1.status());
246 ASSERT_EQ(NodeStatus::SUCCESS, condition_L2.status());
247 ASSERT_EQ(NodeStatus::RUNNING, action_L1.status());
248 ASSERT_EQ(NodeStatus::RUNNING, action_L2.status());
250 ASSERT_EQ(NodeStatus::SUCCESS, parallel_right.status());
251 ASSERT_EQ(NodeStatus::IDLE, condition_R.status());
252 ASSERT_EQ(NodeStatus::IDLE, action_R.status());
254 ASSERT_EQ(NodeStatus::RUNNING, state);
256 std::this_thread::sleep_for(milliseconds(200));
257 state = parallel_root.executeTick();
259 ASSERT_EQ(NodeStatus::IDLE, parallel_left.status());
260 ASSERT_EQ(NodeStatus::IDLE, condition_L1.status());
261 ASSERT_EQ(NodeStatus::IDLE, condition_L2.status());
262 ASSERT_EQ(NodeStatus::IDLE, action_L1.status());
263 ASSERT_EQ(NodeStatus::IDLE, action_L2.status());
265 ASSERT_EQ(NodeStatus::IDLE, parallel_right.status());
266 ASSERT_EQ(NodeStatus::IDLE, condition_R.status());
267 ASSERT_EQ(NodeStatus::IDLE, action_R.status());
269 ASSERT_EQ(NodeStatus::SUCCESS, state);
274 parallel_left.setFailureThreshold(3);
275 parallel_left.setSuccessThreshold(3);
276 condition_L1.setExpectedResult(NodeStatus::FAILURE);
277 condition_L2.setExpectedResult(NodeStatus::FAILURE);
283 ASSERT_EQ(NodeStatus::IDLE, parallel_left.status());
284 ASSERT_EQ(NodeStatus::IDLE, condition_L1.status());
285 ASSERT_EQ(NodeStatus::IDLE, condition_L2.status());
286 ASSERT_EQ(NodeStatus::IDLE, action_L1.status());
287 ASSERT_EQ(NodeStatus::IDLE, action_L2.status());
289 ASSERT_EQ(NodeStatus::IDLE, parallel_right.status());
290 ASSERT_EQ(NodeStatus::IDLE, condition_R.status());
291 ASSERT_EQ(NodeStatus::IDLE, action_R.status());
293 ASSERT_EQ(NodeStatus::FAILURE, state);
298 condition_R.setExpectedResult(NodeStatus::FAILURE);
304 ASSERT_EQ(NodeStatus::IDLE, parallel_left.status());
305 ASSERT_EQ(NodeStatus::IDLE, condition_L1.status());
306 ASSERT_EQ(NodeStatus::IDLE, condition_L2.status());
307 ASSERT_EQ(NodeStatus::IDLE, action_L1.status());
308 ASSERT_EQ(NodeStatus::IDLE, action_L2.status());
310 ASSERT_EQ(NodeStatus::IDLE, parallel_right.status());
311 ASSERT_EQ(NodeStatus::IDLE, condition_R.status());
312 ASSERT_EQ(NodeStatus::IDLE, action_R.status());
314 ASSERT_EQ(NodeStatus::FAILURE, state);
319 parallel_right.setFailureThreshold(2);
320 condition_R.setExpectedResult(NodeStatus::FAILURE);
325 ASSERT_EQ(NodeStatus::RUNNING, parallel_left.status());
326 ASSERT_EQ(NodeStatus::SUCCESS, condition_L1.status());
327 ASSERT_EQ(NodeStatus::SUCCESS, condition_L2.status());
328 ASSERT_EQ(NodeStatus::RUNNING, action_L1.status());
329 ASSERT_EQ(NodeStatus::RUNNING, action_L2.status());
331 ASSERT_EQ(NodeStatus::RUNNING, parallel_right.status());
332 ASSERT_EQ(NodeStatus::FAILURE, condition_R.status());
333 ASSERT_EQ(NodeStatus::RUNNING, action_R.status());
335 ASSERT_EQ(NodeStatus::RUNNING, state);
338 std::this_thread::sleep_for(milliseconds(500));
339 state = parallel_root.executeTick();
341 ASSERT_EQ(NodeStatus::IDLE, parallel_left.status());
342 ASSERT_EQ(NodeStatus::IDLE, condition_L1.status());
343 ASSERT_EQ(NodeStatus::IDLE, condition_L2.status());
344 ASSERT_EQ(NodeStatus::IDLE, action_L1.status());
345 ASSERT_EQ(NodeStatus::IDLE, action_L2.status());
347 ASSERT_EQ(NodeStatus::IDLE, parallel_right.status());
348 ASSERT_EQ(NodeStatus::IDLE, condition_R.status());
349 ASSERT_EQ(NodeStatus::IDLE, action_R.status());
351 ASSERT_EQ(NodeStatus::SUCCESS, state);
356 condition_R.setExpectedResult(NodeStatus::FAILURE);
358 parallel_right.setFailureThreshold(2);
359 parallel_left.setSuccessThreshold(4);
362 std::this_thread::sleep_for(milliseconds(300));
365 ASSERT_EQ(NodeStatus::RUNNING, parallel_left.status());
366 ASSERT_EQ(NodeStatus::SUCCESS, condition_L1.status());
367 ASSERT_EQ(NodeStatus::SUCCESS, condition_L2.status());
368 ASSERT_EQ(NodeStatus::SUCCESS, action_L1.status());
369 ASSERT_EQ(NodeStatus::SUCCESS, action_L2.status());
371 ASSERT_EQ(NodeStatus::RUNNING, parallel_right.status());
374 state = parallel_root.executeTick();
376 ASSERT_EQ(NodeStatus::SUCCESS, parallel_left.status());
377 ASSERT_EQ(NodeStatus::IDLE, condition_L1.status());
378 ASSERT_EQ(NodeStatus::IDLE, condition_L2.status());
379 ASSERT_EQ(NodeStatus::IDLE, action_L1.status());
380 ASSERT_EQ(NodeStatus::IDLE, action_L2.status());
382 ASSERT_EQ(NodeStatus::RUNNING, parallel_right.status());
383 ASSERT_EQ(NodeStatus::RUNNING, action_R.status());
385 ASSERT_EQ(NodeStatus::RUNNING, state);
388 std::this_thread::sleep_for(milliseconds(300));
389 state = parallel_root.executeTick();
391 ASSERT_EQ(NodeStatus::IDLE, parallel_left.status());
392 ASSERT_EQ(NodeStatus::IDLE, action_L1.status());
394 ASSERT_EQ(NodeStatus::IDLE, parallel_right.status());
395 ASSERT_EQ(NodeStatus::IDLE, action_R.status());
397 ASSERT_EQ(NodeStatus::SUCCESS, state);
400 TEST(Parallel, FailingParallel)
403 <root BTCPP_format="4">
404 <BehaviorTree ID="MainTree">
405 <Parallel name="parallel" success_count="1" failure_count="3">
406 <GoodTest name="first"/>
407 <BadTest name="second"/>
408 <SlowTest name="third"/>
417 good_config.
async_delay = std::chrono::milliseconds(200);
422 bad_config.
async_delay = std::chrono::milliseconds(100);
427 slow_config.
async_delay = std::chrono::milliseconds(300);
434 auto state = tree.tickWhileRunning();
449 good_config.
async_delay = std::chrono::milliseconds(300);
454 bad_config.
async_delay = std::chrono::milliseconds(100);
460 <root BTCPP_format="4">
461 <BehaviorTree ID="MainTree">
462 <ParallelAll max_failures="1">
463 <BadTest name="first"/>
464 <GoodTest name="second"/>
465 <GoodTest name="third"/>
472 auto state = tree.tickWhileRunning();
481 <root BTCPP_format="4">
482 <BehaviorTree ID="MainTree">
483 <ParallelAll max_failures="2">
484 <BadTest name="first"/>
485 <GoodTest name="second"/>
486 <GoodTest name="third"/>
493 auto state = tree.tickWhileRunning();
504 <root BTCPP_format="4">
505 <BehaviorTree ID="TestTree">
507 <Script code="test := true"/>
508 <Parallel failure_count="1" success_count="-1">
509 <TestA _skipIf="test == true"/>
519 std::array<int, 1> counters;
525 ASSERT_EQ(0, counters[0]);
531 <root BTCPP_format="4">
532 <BehaviorTree ID="TestTree">
536 <Script code="paused := false"/>
541 <Script code="paused := true; done := false"/>
542 <RetryUntilSuccessful _while="paused" num_attempts="-1" _onHalted="done = true">
544 </RetryUntilSuccessful>
555 auto t1 = std::chrono::system_clock::now();
556 std::chrono::system_clock::time_point done_time;
557 bool done_detected =
false;
559 auto status = tree.tickExactlyOnce();
560 auto toMsec = [](
const auto& t) {
561 return std::chrono::duration_cast<std::chrono::milliseconds>(t).count();
566 std::this_thread::sleep_for(std::chrono::milliseconds(1));
570 if(tree.subtrees.front()->blackboard->get<
bool>(
"done"))
572 done_detected =
true;
573 done_time = std::chrono::system_clock::now();
574 std::cout <<
"detected\n";
577 status = tree.tickExactlyOnce();
579 auto t2 = std::chrono::system_clock::now();
585 const int margin_msec = 40;
587 const int margin_msec = 10;
591 ASSERT_LE(toMsec(done_time - t1) - 150, margin_msec);
593 ASSERT_LE(toMsec(t2 - t1) - 300, margin_msec * 2);