gtest_sequence.cpp
Go to the documentation of this file.
1 /* Copyright (C) 2015-2017 Michele Colledanchise - All Rights Reserved
2 *
3 * Permission is hereby granted, free of charge, to any person obtaining a copy of this software and associated documentation files (the "Software"),
4 * to deal in the Software without restriction, including without limitation the rights to use, copy, modify, merge, publish, distribute, sublicense,
5 * and/or sell copies of the Software, and to permit persons to whom the Software is furnished to do so, subject to the following conditions:
6 * The above copyright notice and this permission notice shall be included in all copies or substantial portions of the Software.
7 *
8 * THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY,
9 * FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER LIABILITY,
10 * WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE SOFTWARE.
11 */
12 
13 #include <gtest/gtest.h>
14 #include "action_test_node.h"
15 #include "condition_test_node.h"
17 
18 using BT::NodeStatus;
19 using std::chrono::milliseconds;
20 
21 struct SimpleSequenceTest : testing::Test
22 {
26 
28  root("root_sequence")
29  , action("action", milliseconds(100))
30  , condition("condition")
31  {
32  root.addChild(&condition);
33  root.addChild(&action);
34  }
36  {
37  haltAllActions(&root);
38  }
39 };
40 
41 struct ComplexSequenceTest : testing::Test
42 {
47 
49 
51  : root("root")
52  , action_1("action_1", milliseconds(100))
53  , condition_1("condition_1")
54  , condition_2("condition_2")
55  , seq_conditions("sequence_conditions")
56  {
57  root.addChild(&seq_conditions);
58  {
59  seq_conditions.addChild(&condition_1);
60  seq_conditions.addChild(&condition_2);
61  }
62  root.addChild(&action_1);
63  }
65  {
66  haltAllActions(&root);
67  }
68 };
69 
70 struct SequenceTripleActionTest : testing::Test
71 {
77 
79  : root("root_sequence")
80  , condition("condition")
81  , action_1("action_1", milliseconds(100))
82  , action_2("action_2")
83  , action_3("action_3", milliseconds(100))
84  {
85  root.addChild(&condition);
86  root.addChild(&action_1);
87  root.addChild(&action_2);
88  root.addChild(&action_3);
89  }
91  {
92  haltAllActions(&root);
93  }
94 };
95 
96 struct ComplexSequence2ActionsTest : testing::Test
97 {
103 
106 
108  : root("root_sequence")
109  , action_1("action_1", milliseconds(100))
110  , action_2("action_2", milliseconds(100))
111  , seq_1("sequence_1")
112  , seq_2("sequence_2")
113  , condition_1("condition_1")
114  , condition_2("condition_2")
115  {
116  root.addChild(&seq_1);
117  {
118  seq_1.addChild(&condition_1);
119  seq_1.addChild(&action_1);
120  }
121  root.addChild(&seq_2);
122  {
123  seq_2.addChild(&condition_2);
124  seq_2.addChild(&action_2);
125  }
126  }
128  {
129  haltAllActions(&root);
130  }
131 };
132 
133 struct SimpleSequenceWithMemoryTest : testing::Test
134 {
138 
140  root("root_sequence")
141  , action("action", milliseconds(100))
142  , condition("condition")
143  {
144  root.addChild(&condition);
145  root.addChild(&action);
146  }
148  {
149  haltAllActions(&root);
150  }
151 };
152 
153 struct ComplexSequenceWithMemoryTest : testing::Test
154 {
156 
159 
162 
165 
167  : root("root_sequence")
168  , action_1("action_1", milliseconds(100))
169  , action_2("action_2", milliseconds(100))
170  , condition_1("condition_1")
171  , condition_2("condition_2")
172  , seq_conditions("sequence_conditions")
173  , seq_actions("sequence_actions")
174  {
175  root.addChild(&seq_conditions);
176  {
177  seq_conditions.addChild(&condition_1);
178  seq_conditions.addChild(&condition_2);
179  }
180  root.addChild(&seq_actions);
181  {
182  seq_actions.addChild(&action_1);
183  seq_actions.addChild(&action_2);
184  }
185  }
187  {
188  haltAllActions(&root);
189  }
190 };
191 
192 struct SimpleParallelTest : testing::Test
193 {
195  BT::AsyncActionTest action_1;
196  BT::ConditionTestNode condition_1;
197 
198  BT::AsyncActionTest action_2;
199  BT::ConditionTestNode condition_2;
200 
202  : root("root_parallel", 4)
203  , action_1("action_1", milliseconds(100))
204  , condition_1("condition_1")
205  , action_2("action_2", milliseconds(100))
206  , condition_2("condition_2")
207  {
208  root.addChild(&condition_1);
209  root.addChild(&action_1);
210  root.addChild(&condition_2);
211  root.addChild(&action_2);
212  }
214  {
215  haltAllActions(&root);
216  }
217 };
218 
219 /****************TESTS START HERE***************************/
220 
221 TEST_F(SimpleSequenceTest, ConditionTrue)
222 {
223  std::cout << "Ticking the root node !" << std::endl << std::endl;
224  // Ticking the root node
225  BT::NodeStatus state = root.executeTick();
226 
227  ASSERT_EQ(NodeStatus::RUNNING, action.status());
228  ASSERT_EQ(NodeStatus::RUNNING, state);
229 }
230 
231 TEST_F(SimpleSequenceTest, ConditionTurnToFalse)
232 {
233  condition.setBoolean(false);
234  BT::NodeStatus state = root.executeTick();
235 
236  state = root.executeTick();
237  ASSERT_EQ(NodeStatus::FAILURE, state);
238  ASSERT_EQ(NodeStatus::IDLE, condition.status());
239  ASSERT_EQ(NodeStatus::IDLE, action.status());
240 }
241 
242 TEST_F(ComplexSequenceTest, ComplexSequenceConditionsTrue)
243 {
244  BT::NodeStatus state = root.executeTick();
245 
246  ASSERT_EQ(NodeStatus::RUNNING, state);
247  ASSERT_EQ(NodeStatus::SUCCESS, seq_conditions.status());
248  ASSERT_EQ(NodeStatus::IDLE, condition_1.status());
249  ASSERT_EQ(NodeStatus::IDLE, condition_1.status());
250  ASSERT_EQ(NodeStatus::RUNNING, action_1.status());
251 }
252 
254 {
255  using namespace BT;
256  using namespace std::chrono;
257  const auto timeout = system_clock::now() + milliseconds(650);
258 
259  action_1.setTime( milliseconds(300) );
260  action_3.setTime( milliseconds(300) );
261  // the sequence is supposed to finish in (300 ms * 2) = 600 ms
262 
263  // first tick
264  NodeStatus state = root.executeTick();
265 
266  ASSERT_EQ(NodeStatus::RUNNING, state);
267  ASSERT_EQ(NodeStatus::RUNNING, action_1.status());
268  ASSERT_EQ(NodeStatus::IDLE, action_2.status());
269  ASSERT_EQ(NodeStatus::IDLE, action_3.status());
270 
271  // continue until succesful
272  while (state != NodeStatus::SUCCESS && system_clock::now() < timeout)
273  {
274  std::this_thread::sleep_for(milliseconds(10));
275  state = root.executeTick();
276  }
277 
278  ASSERT_EQ(NodeStatus::SUCCESS, state);
279 
280  // Condition is called only once
281  ASSERT_EQ(condition.tickCount(), 1);
282  // all the actions are called only once
283  ASSERT_EQ(action_1.tickCount(), 1);
284  ASSERT_EQ(action_2.tickCount(), 1);
285  ASSERT_EQ(action_3.tickCount(), 1);
286 
287  ASSERT_EQ(NodeStatus::IDLE, action_1.status());
288  ASSERT_EQ(NodeStatus::IDLE, action_2.status());
289  ASSERT_EQ(NodeStatus::IDLE, action_3.status());
290  ASSERT_TRUE(system_clock::now() < timeout); // no timeout should occur
291 }
292 
294 {
295  BT::NodeStatus state = root.executeTick();
296 
297  state = root.executeTick();
298 
299  ASSERT_EQ(NodeStatus::RUNNING, state);
300  ASSERT_EQ(NodeStatus::RUNNING, seq_1.status());
301  ASSERT_EQ(NodeStatus::SUCCESS, condition_1.status());
302  ASSERT_EQ(NodeStatus::RUNNING, action_1.status());
303  ASSERT_EQ(NodeStatus::IDLE, seq_2.status());
304  ASSERT_EQ(NodeStatus::IDLE, condition_2.status());
305  ASSERT_EQ(NodeStatus::IDLE, action_2.status());
306 
307  std::this_thread::sleep_for(milliseconds(300));
308  state = root.executeTick();
309 
310  ASSERT_EQ(NodeStatus::RUNNING, state);
311  ASSERT_EQ(NodeStatus::SUCCESS, seq_1.status());
312  ASSERT_EQ(NodeStatus::IDLE, condition_1.status());
313  ASSERT_EQ(NodeStatus::IDLE, action_1.status());
314  ASSERT_EQ(NodeStatus::RUNNING, seq_2.status());
315  ASSERT_EQ(NodeStatus::SUCCESS, condition_2.status());
316  ASSERT_EQ(NodeStatus::RUNNING, action_2.status());
317 
318  state = root.executeTick();
319 }
320 
321 TEST_F(ComplexSequenceTest, ComplexSequenceConditions1ToFalse)
322 {
323  BT::NodeStatus state = root.executeTick();
324 
325  condition_1.setBoolean(false);
326 
327  state = root.executeTick();
328 
329  ASSERT_EQ(NodeStatus::FAILURE, state);
330  ASSERT_EQ(NodeStatus::IDLE, seq_conditions.status());
331  ASSERT_EQ(NodeStatus::IDLE, condition_1.status());
332  ASSERT_EQ(NodeStatus::IDLE, condition_2.status());
333  ASSERT_EQ(NodeStatus::IDLE, action_1.status());
334 }
335 
336 TEST_F(ComplexSequenceTest, ComplexSequenceConditions2ToFalse)
337 {
338  BT::NodeStatus state = root.executeTick();
339 
340  condition_2.setBoolean(false);
341 
342  state = root.executeTick();
343 
344  ASSERT_EQ(NodeStatus::FAILURE, state);
345  ASSERT_EQ(NodeStatus::IDLE, seq_conditions.status());
346  ASSERT_EQ(NodeStatus::IDLE, condition_1.status());
347  ASSERT_EQ(NodeStatus::IDLE, condition_2.status());
348  ASSERT_EQ(NodeStatus::IDLE, action_1.status());
349 }
350 
352 {
353  BT::NodeStatus state = root.executeTick();
354  std::this_thread::sleep_for( milliseconds(50) );
355 
356  ASSERT_EQ(NodeStatus::RUNNING, state);
357  ASSERT_EQ(NodeStatus::SUCCESS, condition.status());
358  ASSERT_EQ(NodeStatus::RUNNING, action.status());
359 }
360 
361 TEST_F(SimpleSequenceWithMemoryTest, ConditionTurnToFalse)
362 {
363  BT::NodeStatus state = root.executeTick();
364 
365  ASSERT_EQ(NodeStatus::RUNNING, state);
366  ASSERT_EQ(NodeStatus::SUCCESS, condition.status());
367  ASSERT_EQ(NodeStatus::RUNNING, action.status());
368 
369  condition.setBoolean(false);
370  state = root.executeTick();
371 
372  ASSERT_EQ(NodeStatus::RUNNING, state);
373  ASSERT_EQ(NodeStatus::SUCCESS, condition.status());
374  ASSERT_EQ(NodeStatus::RUNNING, action.status());
375 }
376 
378 {
379  BT::NodeStatus state = root.executeTick();
380 
381  ASSERT_EQ(NodeStatus::RUNNING, state);
382  ASSERT_EQ(NodeStatus::SUCCESS, seq_conditions.status());
383  ASSERT_EQ(NodeStatus::IDLE, condition_1.status());
384  ASSERT_EQ(NodeStatus::IDLE, condition_2.status());
385  ASSERT_EQ(NodeStatus::RUNNING, seq_actions.status());
386  ASSERT_EQ(NodeStatus::RUNNING, action_1.status());
387  ASSERT_EQ(NodeStatus::IDLE, action_2.status());
388 }
389 
391 {
392  BT::NodeStatus state = root.executeTick();
393 
394  condition_1.setBoolean(false);
395  state = root.executeTick();
396  // change in condition_1 does not affect the state of the tree,
397  // since the seq_conditions was executed already
398  ASSERT_EQ(NodeStatus::RUNNING, state);
399  ASSERT_EQ(NodeStatus::SUCCESS, seq_conditions.status());
400  ASSERT_EQ(NodeStatus::IDLE, condition_1.status());
401  ASSERT_EQ(NodeStatus::IDLE, condition_2.status());
402  ASSERT_EQ(NodeStatus::RUNNING, seq_actions.status());
403  ASSERT_EQ(NodeStatus::RUNNING, action_1.status());
404  ASSERT_EQ(NodeStatus::IDLE, action_2.status());
405 }
406 
408 {
409  BT::NodeStatus state = root.executeTick();
410 
411  condition_2.setBoolean(false);
412  state = root.executeTick();
413  // change in condition_2 does not affect the state of the tree,
414  // since the seq_conditions was executed already
415  ASSERT_EQ(NodeStatus::RUNNING, state);
416  ASSERT_EQ(NodeStatus::SUCCESS, seq_conditions.status());
417  ASSERT_EQ(NodeStatus::IDLE, condition_1.status());
418  ASSERT_EQ(NodeStatus::IDLE, condition_2.status());
419  ASSERT_EQ(NodeStatus::RUNNING, seq_actions.status());
420  ASSERT_EQ(NodeStatus::RUNNING, action_1.status());
421  ASSERT_EQ(NodeStatus::IDLE, action_2.status());
422 }
423 
425 {
426  root.executeTick();
427 
428  condition_2.setBoolean(false);
429  root.executeTick();
430 
431  // change in condition_2 does not affect the state of the tree,
432  // since the seq_conditions was executed already
433  ASSERT_EQ(NodeStatus::SUCCESS, seq_conditions.status());
434  ASSERT_EQ(NodeStatus::IDLE, condition_1.status());
435  ASSERT_EQ(NodeStatus::IDLE, condition_2.status());
436  ASSERT_EQ(NodeStatus::RUNNING, seq_actions.status());
437  ASSERT_EQ(NodeStatus::RUNNING, action_1.status());
438  ASSERT_EQ(NodeStatus::IDLE, action_2.status());
439 
440  std::this_thread::sleep_for(milliseconds(150));
441  root.executeTick();
442 
443  ASSERT_EQ(NodeStatus::SUCCESS, seq_conditions.status());
444  ASSERT_EQ(NodeStatus::IDLE, condition_1.status());
445  ASSERT_EQ(NodeStatus::IDLE, condition_2.status());
446  ASSERT_EQ(NodeStatus::RUNNING, seq_actions.status());
447  ASSERT_EQ(NodeStatus::SUCCESS, action_1.status());
448  ASSERT_EQ(NodeStatus::RUNNING, action_2.status());
449 
450  std::this_thread::sleep_for(milliseconds(150));
451  root.executeTick();
452 
453  ASSERT_EQ(NodeStatus::SUCCESS, root.status());
454  ASSERT_EQ(NodeStatus::IDLE, seq_conditions.status());
455  ASSERT_EQ(NodeStatus::IDLE, condition_1.status());
456  ASSERT_EQ(NodeStatus::IDLE, condition_2.status());
457  ASSERT_EQ(NodeStatus::IDLE, seq_actions.status());
458  ASSERT_EQ(NodeStatus::IDLE, action_1.status());
459  ASSERT_EQ(NodeStatus::IDLE, action_2.status());
460 }
BT::ConditionTestNode condition_1
BT::AsyncActionTest action_2
The SequenceStarNode is used to tick children in an ordered sequence. If any child returns RUNNING...
BT::ConditionTestNode condition_1
BT::ConditionTestNode condition_2
BT::SequenceNode root
BT::SequenceStarNode seq_conditions
BT::ConditionTestNode condition_1
TEST_F(SimpleSequenceTest, ConditionTrue)
BT::AsyncActionTest action_1
void setBoolean(bool boolean_value)
BT::ConditionTestNode condition_2
BT::AsyncActionTest action
BT::AsyncActionTest action_1
void haltAllActions(TreeNode *root_node)
BT::ReactiveSequence root
BT::ConditionTestNode condition
BT::SequenceStarNode seq_actions
BT::SyncActionTest action_2
BT::ConditionTestNode condition_2
BT::AsyncActionTest action_3
void addChild(TreeNode *child)
The method used to add nodes to the children vector.
BT::SequenceNode seq_conditions
BT::ConditionTestNode condition
BT::ConditionTestNode condition
NodeStatus status() const
Definition: tree_node.cpp:56
BT::AsyncActionTest action_1
NodeStatus
Definition: basic_types.h:35
The ReactiveSequence is similar to a ParallelNode. All the children are ticked from first to last: ...
virtual BT::NodeStatus executeTick()
The method that should be used to invoke tick() and setStatus();.
Definition: tree_node.cpp:33
The SequenceNode is used to tick children in an ordered sequence. If any child returns RUNNING...
Definition: sequence_node.h:34


behaviortree_cpp
Author(s): Michele Colledanchise, Davide Faconti
autogenerated on Sat Jun 8 2019 18:04:05