gtest_fallback.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 SimpleFallbackTest : testing::Test
22 {
26 
28  root("root_fallback")
29  , condition("condition")
30  , action("action", milliseconds(100) )
31  {
32  root.addChild(&condition);
33  root.addChild(&action);
34  }
36  {
37 
38  }
39 };
40 
41 struct ReactiveFallbackTest : testing::Test
42 {
47 
49  : root("root_first")
50  , condition_1("condition_1")
51  , condition_2("condition_2")
52  , action_1("action_1", milliseconds(100) )
53  {
54  root.addChild(&condition_1);
55  root.addChild(&condition_2);
56  root.addChild(&action_1);
57  }
59  {
60 
61  }
62 };
63 
64 struct SimpleFallbackWithMemoryTest : testing::Test
65 {
69 
71  root("root_sequence")
72  , action("action", milliseconds(100) )
73  , condition("condition")
74  {
75  root.addChild(&condition);
76  root.addChild(&action);
77  }
79  {
80 
81  }
82 };
83 
84 struct ComplexFallbackWithMemoryTest : testing::Test
85 {
87 
90 
93 
96 
98  : root("root_fallback")
99  , action_1("action_1", milliseconds(100) )
100  , action_2("action_2", milliseconds(100) )
101  , condition_1("condition_1")
102  , condition_2("condition_2")
103  , fal_conditions("fallback_conditions")
104  , fal_actions("fallback_actions")
105  {
106  root.addChild(&fal_conditions);
107  {
108  fal_conditions.addChild(&condition_1);
109  fal_conditions.addChild(&condition_2);
110  }
111  root.addChild(&fal_actions);
112  {
113  fal_actions.addChild(&action_1);
114  fal_actions.addChild(&action_2);
115  }
116  }
118  {
119 
120  }
121 };
122 
123 /****************TESTS START HERE***************************/
124 
125 TEST_F(SimpleFallbackTest, ConditionTrue)
126 {
127  // Ticking the root node
128  condition.setExpectedResult(NodeStatus::SUCCESS);
129  BT::NodeStatus state = root.executeTick();
130 
131  ASSERT_EQ(NodeStatus::SUCCESS, state);
132  ASSERT_EQ(NodeStatus::IDLE, condition.status());
133  ASSERT_EQ(NodeStatus::IDLE, action.status());
134 }
135 
136 TEST_F(SimpleFallbackTest, ConditionChangeWhileRunning)
137 {
139 
140  condition.setExpectedResult(NodeStatus::FAILURE);
141  state = root.executeTick();
142 
143  ASSERT_EQ(NodeStatus::RUNNING, state);
144  ASSERT_EQ(NodeStatus::FAILURE, condition.status());
145  ASSERT_EQ(NodeStatus::RUNNING, action.status());
146 
147  condition.setExpectedResult(NodeStatus::SUCCESS);
148  state = root.executeTick();
149 
150  ASSERT_EQ(NodeStatus::RUNNING, state);
151  ASSERT_EQ(NodeStatus::FAILURE, condition.status());
152  ASSERT_EQ(NodeStatus::RUNNING, action.status());
153 }
154 
155 TEST_F(ReactiveFallbackTest, Condition1ToTrue)
156 {
157  condition_1.setExpectedResult(NodeStatus::FAILURE);
158  condition_2.setExpectedResult(NodeStatus::FAILURE);
159 
160  BT::NodeStatus state = root.executeTick();
161 
162  ASSERT_EQ(NodeStatus::RUNNING, state);
163  ASSERT_EQ(NodeStatus::FAILURE, condition_1.status());
164  ASSERT_EQ(NodeStatus::FAILURE, condition_2.status());
165  ASSERT_EQ(NodeStatus::RUNNING, action_1.status());
166 
167  condition_1.setExpectedResult(NodeStatus::SUCCESS);
168 
169  state = root.executeTick();
170 
171  ASSERT_EQ(NodeStatus::SUCCESS, state);
172  ASSERT_EQ(NodeStatus::IDLE, condition_1.status());
173  ASSERT_EQ(NodeStatus::IDLE, condition_2.status());
174  ASSERT_EQ(NodeStatus::IDLE, action_1.status());
175 }
176 
177 TEST_F(ReactiveFallbackTest, Condition2ToTrue)
178 {
179  condition_1.setExpectedResult(NodeStatus::FAILURE);
180  condition_2.setExpectedResult(NodeStatus::FAILURE);
181 
182  BT::NodeStatus state = root.executeTick();
183 
184  ASSERT_EQ(NodeStatus::RUNNING, state);
185  ASSERT_EQ(NodeStatus::FAILURE, condition_1.status());
186  ASSERT_EQ(NodeStatus::FAILURE, condition_2.status());
187  ASSERT_EQ(NodeStatus::RUNNING, action_1.status());
188 
189  condition_2.setExpectedResult(NodeStatus::SUCCESS);
190 
191  state = root.executeTick();
192 
193  ASSERT_EQ(NodeStatus::SUCCESS, state);
194  ASSERT_EQ(NodeStatus::IDLE, condition_1.status());
195  ASSERT_EQ(NodeStatus::IDLE, condition_2.status());
196  ASSERT_EQ(NodeStatus::IDLE, action_1.status());
197 }
198 
200 {
201  condition.setExpectedResult(NodeStatus::FAILURE);
202  BT::NodeStatus state = root.executeTick();
203 
204  ASSERT_EQ(NodeStatus::RUNNING, state);
205  ASSERT_EQ(NodeStatus::FAILURE, condition.status());
206  ASSERT_EQ(NodeStatus::RUNNING, action.status());
207 }
208 
210 {
211  condition.setExpectedResult(NodeStatus::FAILURE);
212  BT::NodeStatus state = root.executeTick();
213 
214  ASSERT_EQ(NodeStatus::RUNNING, state);
215  ASSERT_EQ(NodeStatus::FAILURE, condition.status());
216  ASSERT_EQ(NodeStatus::RUNNING, action.status());
217 
218  condition.setExpectedResult(NodeStatus::SUCCESS);
219  state = root.executeTick();
220 
221  ASSERT_EQ(NodeStatus::RUNNING, state);
222  ASSERT_EQ(NodeStatus::FAILURE, condition.status());
223  ASSERT_EQ(NodeStatus::RUNNING, action.status());
224 }
225 
227 {
228  BT::NodeStatus state = root.executeTick();
229 
230  ASSERT_EQ(NodeStatus::SUCCESS, state);
231  ASSERT_EQ(NodeStatus::IDLE, fal_conditions.status());
232  ASSERT_EQ(NodeStatus::IDLE, condition_1.status());
233  ASSERT_EQ(NodeStatus::IDLE, condition_2.status());
234  ASSERT_EQ(NodeStatus::IDLE, fal_actions.status());
235  ASSERT_EQ(NodeStatus::IDLE, action_1.status());
236  ASSERT_EQ(NodeStatus::IDLE, action_2.status());
237 }
238 
240 {
241  condition_1.setExpectedResult(NodeStatus::FAILURE);
242  BT::NodeStatus state = root.executeTick();
243 
244  ASSERT_EQ(NodeStatus::SUCCESS, state);
245  ASSERT_EQ(NodeStatus::IDLE, fal_conditions.status());
246  ASSERT_EQ(NodeStatus::IDLE, condition_1.status());
247  ASSERT_EQ(NodeStatus::IDLE, condition_2.status());
248  ASSERT_EQ(NodeStatus::IDLE, fal_actions.status());
249  ASSERT_EQ(NodeStatus::IDLE, action_1.status());
250  ASSERT_EQ(NodeStatus::IDLE, action_2.status());
251 }
252 
254 {
255  condition_1.setExpectedResult(NodeStatus::FAILURE);
256  condition_2.setExpectedResult(NodeStatus::FAILURE);
257  BT::NodeStatus state = root.executeTick();
258 
259  ASSERT_EQ(NodeStatus::RUNNING, state);
260  ASSERT_EQ(NodeStatus::FAILURE, fal_conditions.status());
261  ASSERT_EQ(NodeStatus::IDLE, condition_1.status());
262  ASSERT_EQ(NodeStatus::IDLE, condition_2.status());
263  ASSERT_EQ(NodeStatus::RUNNING, fal_actions.status());
264  ASSERT_EQ(NodeStatus::RUNNING, action_1.status());
265  ASSERT_EQ(NodeStatus::IDLE, action_2.status());
266 }
267 
269 {
270  condition_1.setExpectedResult(NodeStatus::FAILURE);
271  condition_2.setExpectedResult(NodeStatus::FAILURE);
272  BT::NodeStatus state = root.executeTick();
273 
274  condition_1.setExpectedResult(NodeStatus::SUCCESS);
275  state = root.executeTick();
276 
277  ASSERT_EQ(NodeStatus::RUNNING, state);
278  ASSERT_EQ(NodeStatus::FAILURE, fal_conditions.status());
279  ASSERT_EQ(NodeStatus::IDLE, condition_1.status());
280  ASSERT_EQ(NodeStatus::IDLE, condition_2.status());
281  ASSERT_EQ(NodeStatus::RUNNING, fal_actions.status());
282  ASSERT_EQ(NodeStatus::RUNNING, action_1.status());
283  ASSERT_EQ(NodeStatus::IDLE, action_2.status());
284 }
285 
287 {
288  condition_1.setExpectedResult(NodeStatus::FAILURE);
289  condition_2.setExpectedResult(NodeStatus::FAILURE);
290  BT::NodeStatus state = root.executeTick();
291 
292  condition_2.setExpectedResult(NodeStatus::SUCCESS);
293  state = root.executeTick();
294 
295  ASSERT_EQ(NodeStatus::RUNNING, state);
296  ASSERT_EQ(NodeStatus::FAILURE, fal_conditions.status());
297  ASSERT_EQ(NodeStatus::IDLE, condition_1.status());
298  ASSERT_EQ(NodeStatus::IDLE, condition_2.status());
299  ASSERT_EQ(NodeStatus::RUNNING, fal_actions.status());
300  ASSERT_EQ(NodeStatus::RUNNING, action_1.status());
301  ASSERT_EQ(NodeStatus::IDLE, action_2.status());
302 }
303 
305 {
306  action_1.setExpectedResult(NodeStatus::FAILURE);
307  action_2.setExpectedResult(NodeStatus::SUCCESS);
308  condition_1.setExpectedResult(NodeStatus::FAILURE);
309  condition_2.setExpectedResult(NodeStatus::FAILURE);
310 
311  BT::NodeStatus state = root.executeTick();
312 
313  state = root.executeTick();
314  std::this_thread::sleep_for(std::chrono::milliseconds(500));
315  state = root.executeTick();
316 
317  ASSERT_EQ(NodeStatus::RUNNING, state);
318  ASSERT_EQ(NodeStatus::FAILURE, fal_conditions.status());
319  ASSERT_EQ(NodeStatus::IDLE, condition_1.status());
320  ASSERT_EQ(NodeStatus::IDLE, condition_2.status());
321  ASSERT_EQ(NodeStatus::RUNNING, fal_actions.status());
322  ASSERT_EQ(NodeStatus::FAILURE, action_1.status());
323  ASSERT_EQ(NodeStatus::RUNNING, action_2.status());
324 }
BT::AsyncActionTest action_1
BT::AsyncActionTest action
BT::ConditionTestNode condition
BT::ConditionTestNode condition
BT::AsyncActionTest action_2
BT::ReactiveFallback root
BT::ConditionTestNode condition_1
BT::ConditionTestNode condition_2
void setExpectedResult(NodeStatus res)
BT::AsyncActionTest action_1
BT::FallbackNode root
void addChild(TreeNode *child)
The method used to add nodes to the children vector.
The ReactiveFallback is similar to a ParallelNode. All the children are ticked from first to last: ...
NodeStatus status() const
Definition: tree_node.cpp:56
BT::AsyncActionTest action
NodeStatus
Definition: basic_types.h:35
BT::ConditionTestNode condition_2
virtual BT::NodeStatus executeTick()
The method that should be used to invoke tick() and setStatus();.
Definition: tree_node.cpp:33
The FallbackNode is used to try different strategies, until one succeeds. If any child returns RUNNIN...
Definition: fallback_node.h:33
BT::ConditionTestNode condition_1
TEST_F(SimpleFallbackTest, ConditionTrue)


behaviotree_cpp_v3
Author(s): Michele Colledanchise, Davide Faconti
autogenerated on Tue May 4 2021 02:56:24