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 
20 struct SimpleFallbackTest : testing::Test
21 {
25 
26  SimpleFallbackTest() : root("root_fallback"), action("action"), condition("condition")
27  {
28  root.addChild(&condition);
29  root.addChild(&action);
30  }
32  {
33  haltAllActions(&root);
34  }
35 };
36 
37 struct ComplexFallbackTest : testing::Test
38 {
43 
45 
47  : root("root_fallback")
48  , action_1("action_1")
49  , condition_1("condition_1")
50  , condition_2("condition_2")
51  , fal_conditions("fallback_conditions")
52  {
53  root.addChild(&fal_conditions);
54  {
55  fal_conditions.addChild(&condition_1);
56  fal_conditions.addChild(&condition_2);
57  }
58  root.addChild(&action_1);
59  }
61  {
62  haltAllActions(&root);
63  }
64 };
65 
66 struct SimpleFallbackWithMemoryTest : testing::Test
67 {
71 
72  SimpleFallbackWithMemoryTest() : root("root_sequence"), action("action"), condition("condition")
73  {
74  root.addChild(&condition);
75  root.addChild(&action);
76  }
78  {
79  haltAllActions(&root);
80  }
81 };
82 
83 struct ComplexFallbackWithMemoryTest : testing::Test
84 {
86 
89 
92 
95 
97  : root("root_fallback")
98  , action_1("action_1")
99  , action_2("action_2")
100  , condition_1("condition_1")
101  , condition_2("condition_2")
102  , fal_conditions("fallback_conditions")
103  , fal_actions("fallback_actions")
104  {
105  root.addChild(&fal_conditions);
106  {
107  fal_conditions.addChild(&condition_1);
108  fal_conditions.addChild(&condition_2);
109  }
110  root.addChild(&fal_actions);
111  {
112  fal_actions.addChild(&action_1);
113  fal_actions.addChild(&action_2);
114  }
115  }
117  {
118  haltAllActions(&root);
119  }
120 };
121 
122 /****************TESTS START HERE***************************/
123 
124 TEST_F(SimpleFallbackTest, ConditionTrue)
125 {
126  std::cout << "Ticking the root node !" << std::endl << std::endl;
127  // Ticking the root node
128  condition.setBoolean(true);
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, ConditionToFalse)
137 {
138  condition.setBoolean(false);
139 
140  BT::NodeStatus state = root.executeTick();
141  condition.setBoolean(true);
142 
143  state = root.executeTick();
144 
145  ASSERT_EQ(NodeStatus::SUCCESS, state);
146  ASSERT_EQ(NodeStatus::IDLE, condition.status());
147  ASSERT_EQ(NodeStatus::IDLE, action.status());
148 }
149 
150 TEST_F(ComplexFallbackTest, Condition1ToTrue)
151 {
152  condition_1.setBoolean(false);
153  condition_2.setBoolean(false);
154 
155  BT::NodeStatus state = root.executeTick();
156 
157  ASSERT_EQ(NodeStatus::RUNNING, state);
158  ASSERT_EQ(NodeStatus::FAILURE, fal_conditions.status());
159  ASSERT_EQ(NodeStatus::IDLE, condition_1.status());
160  ASSERT_EQ(NodeStatus::IDLE, condition_2.status());
161  ASSERT_EQ(NodeStatus::RUNNING, action_1.status());
162 
163  condition_1.setBoolean(true);
164 
165  state = root.executeTick();
166 
167  ASSERT_EQ(NodeStatus::SUCCESS, state);
168  ASSERT_EQ(NodeStatus::IDLE, fal_conditions.status());
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 }
173 
174 TEST_F(ComplexFallbackTest, Condition2ToTrue)
175 {
176  condition_1.setBoolean(false);
177  condition_2.setBoolean(false);
178 
179  BT::NodeStatus state = root.executeTick();
180 
181  ASSERT_EQ(NodeStatus::RUNNING, state);
182  ASSERT_EQ(NodeStatus::FAILURE, fal_conditions.status());
183  ASSERT_EQ(NodeStatus::IDLE, condition_1.status());
184  ASSERT_EQ(NodeStatus::IDLE, condition_2.status());
185  ASSERT_EQ(NodeStatus::RUNNING, action_1.status());
186 
187  condition_2.setBoolean(true);
188 
189  state = root.executeTick();
190 
191  ASSERT_EQ(NodeStatus::SUCCESS, state);
192  ASSERT_EQ(NodeStatus::IDLE, fal_conditions.status());
193  ASSERT_EQ(NodeStatus::IDLE, condition_1.status());
194  ASSERT_EQ(NodeStatus::IDLE, condition_2.status());
195  ASSERT_EQ(NodeStatus::IDLE, action_1.status());
196 }
197 
199 {
200  condition.setBoolean(false);
201  BT::NodeStatus state = root.executeTick();
202  std::this_thread::sleep_for(std::chrono::milliseconds(100));
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.setBoolean(false);
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.setBoolean(true);
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.setBoolean(false);
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.setBoolean(false);
256  condition_2.setBoolean(false);
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.setBoolean(false);
271  condition_2.setBoolean(false);
272  BT::NodeStatus state = root.executeTick();
273 
274  condition_1.setBoolean(true);
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.setBoolean(false);
289  condition_2.setBoolean(false);
290  BT::NodeStatus state = root.executeTick();
291 
292  condition_2.setBoolean(true);
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.setBoolean(false);
307  condition_1.setBoolean(false);
308  condition_2.setBoolean(false);
309 
310  BT::NodeStatus state = root.executeTick();
311 
312  state = root.executeTick();
313  std::this_thread::sleep_for(std::chrono::milliseconds(500));
314  state = root.executeTick();
315 
316  ASSERT_EQ(NodeStatus::RUNNING, state);
317  ASSERT_EQ(NodeStatus::FAILURE, fal_conditions.status());
318  ASSERT_EQ(NodeStatus::IDLE, condition_1.status());
319  ASSERT_EQ(NodeStatus::IDLE, condition_2.status());
320  ASSERT_EQ(NodeStatus::RUNNING, fal_actions.status());
321  ASSERT_EQ(NodeStatus::FAILURE, action_1.status());
322  ASSERT_EQ(NodeStatus::RUNNING, action_2.status());
323 }
BT::FallbackStarNode fal_conditions
BT::AsyncActionTest action_1
BT::AsyncActionTest action
BT::ConditionTestNode condition
BT::ConditionTestNode condition
BT::FallbackStarNode root
void setBoolean(bool boolean_value)
BT::AsyncActionTest action_2
BT::ConditionTestNode condition_2
BT::AsyncActionTest action_1
BT::FallbackNode fal_conditions
void haltAllActions(TreeNode *root_node)
The FallbackStarNode is used to try different strategies, until one succeed. If any child returns RUN...
BT::FallbackNode root
BT::ConditionTestNode condition_1
BT::FallbackNode root
void addChild(TreeNode *child)
BT::FallbackStarNode fal_actions
NodeStatus status() const
Definition: tree_node.cpp:75
BT::AsyncActionTest action
NodeStatus
Definition: basic_types.h:28
BT::ConditionTestNode condition_2
virtual BT::NodeStatus executeTick()
The method that will be executed to invoke tick(); and setStatus();.
Definition: tree_node.cpp:35
The FallbackNode is used to try different strategies, until one succeed. If any child returns RUNNING...
Definition: fallback_node.h:35
BT::ConditionTestNode condition_1
TEST_F(SimpleFallbackTest, ConditionTrue)


behaviortree_cpp
Author(s): Michele Colledanchise, Davide Faconti
autogenerated on Sun Feb 3 2019 03:14:32