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"
18 
19 using BT::NodeStatus;
20 using std::chrono::milliseconds;
21 
22 struct SimpleFallbackTest : testing::Test
23 {
27 
29  root("root_fallback"), condition("condition"), action("action", milliseconds(100))
30  {
31  root.addChild(&condition);
32  root.addChild(&action);
33  }
35  {}
36 };
37 
38 struct ReactiveFallbackTest : testing::Test
39 {
44 
46  root("root_first"),
47  condition_1("condition_1"),
48  condition_2("condition_2"),
49  action_1("action_1", milliseconds(100))
50  {
51  root.addChild(&condition_1);
52  root.addChild(&condition_2);
53  root.addChild(&action_1);
54  }
56  {}
57 };
58 
59 struct SimpleFallbackWithMemoryTest : testing::Test
60 {
64 
66  root("root_sequence"), action("action", milliseconds(100)), condition("condition")
67  {
68  root.addChild(&condition);
69  root.addChild(&action);
70  }
72  {}
73 };
74 
75 struct ComplexFallbackWithMemoryTest : testing::Test
76 {
78 
81 
84 
87 
89  root("root_fallback"),
90  action_1("action_1", milliseconds(100)),
91  action_2("action_2", milliseconds(100)),
92  condition_1("condition_1"),
93  condition_2("condition_2"),
94  fal_conditions("fallback_conditions"),
95  fal_actions("fallback_actions")
96  {
97  root.addChild(&fal_conditions);
98  {
99  fal_conditions.addChild(&condition_1);
100  fal_conditions.addChild(&condition_2);
101  }
102  root.addChild(&fal_actions);
103  {
104  fal_actions.addChild(&action_1);
105  fal_actions.addChild(&action_2);
106  }
107  }
109  {}
110 };
111 
112 /****************TESTS START HERE***************************/
113 
114 TEST_F(SimpleFallbackTest, ConditionTrue)
115 {
116  // Ticking the root node
117  condition.setExpectedResult(NodeStatus::SUCCESS);
118  BT::NodeStatus state = root.executeTick();
119 
120  ASSERT_EQ(NodeStatus::SUCCESS, state);
121  ASSERT_EQ(NodeStatus::IDLE, condition.status());
122  ASSERT_EQ(NodeStatus::IDLE, action.status());
123 }
124 
125 TEST_F(SimpleFallbackTest, ConditionChangeWhileRunning)
126 {
128 
129  condition.setExpectedResult(NodeStatus::FAILURE);
130  state = root.executeTick();
131 
132  ASSERT_EQ(NodeStatus::RUNNING, state);
133  ASSERT_EQ(NodeStatus::FAILURE, condition.status());
134  ASSERT_EQ(NodeStatus::RUNNING, action.status());
135 
136  condition.setExpectedResult(NodeStatus::SUCCESS);
137  state = root.executeTick();
138 
139  ASSERT_EQ(NodeStatus::RUNNING, state);
140  ASSERT_EQ(NodeStatus::FAILURE, condition.status());
141  ASSERT_EQ(NodeStatus::RUNNING, action.status());
142 }
143 
144 TEST_F(ReactiveFallbackTest, Condition1ToTrue)
145 {
146  condition_1.setExpectedResult(NodeStatus::FAILURE);
147  condition_2.setExpectedResult(NodeStatus::FAILURE);
148 
149  BT::NodeStatus state = root.executeTick();
150 
151  ASSERT_EQ(NodeStatus::RUNNING, state);
152  ASSERT_EQ(NodeStatus::FAILURE, condition_1.status());
153  ASSERT_EQ(NodeStatus::FAILURE, condition_2.status());
154  ASSERT_EQ(NodeStatus::RUNNING, action_1.status());
155 
156  condition_1.setExpectedResult(NodeStatus::SUCCESS);
157 
158  state = root.executeTick();
159 
160  ASSERT_EQ(NodeStatus::SUCCESS, state);
161  ASSERT_EQ(NodeStatus::IDLE, condition_1.status());
162  ASSERT_EQ(NodeStatus::IDLE, condition_2.status());
163  ASSERT_EQ(NodeStatus::IDLE, action_1.status());
164 }
165 
166 TEST_F(ReactiveFallbackTest, Condition2ToTrue)
167 {
168  condition_1.setExpectedResult(NodeStatus::FAILURE);
169  condition_2.setExpectedResult(NodeStatus::FAILURE);
170 
171  BT::NodeStatus state = root.executeTick();
172 
173  ASSERT_EQ(NodeStatus::RUNNING, state);
174  ASSERT_EQ(NodeStatus::FAILURE, condition_1.status());
175  ASSERT_EQ(NodeStatus::FAILURE, condition_2.status());
176  ASSERT_EQ(NodeStatus::RUNNING, action_1.status());
177 
178  condition_2.setExpectedResult(NodeStatus::SUCCESS);
179 
180  state = root.executeTick();
181 
182  ASSERT_EQ(NodeStatus::SUCCESS, state);
183  ASSERT_EQ(NodeStatus::IDLE, condition_1.status());
184  ASSERT_EQ(NodeStatus::IDLE, condition_2.status());
185  ASSERT_EQ(NodeStatus::IDLE, action_1.status());
186 }
187 
189 {
190  condition.setExpectedResult(NodeStatus::FAILURE);
191  BT::NodeStatus state = root.executeTick();
192 
193  ASSERT_EQ(NodeStatus::RUNNING, state);
194  ASSERT_EQ(NodeStatus::FAILURE, condition.status());
195  ASSERT_EQ(NodeStatus::RUNNING, action.status());
196 }
197 
199 {
200  condition.setExpectedResult(NodeStatus::FAILURE);
201  BT::NodeStatus state = root.executeTick();
202 
203  ASSERT_EQ(NodeStatus::RUNNING, state);
204  ASSERT_EQ(NodeStatus::FAILURE, condition.status());
205  ASSERT_EQ(NodeStatus::RUNNING, action.status());
206 
207  condition.setExpectedResult(NodeStatus::SUCCESS);
208  state = root.executeTick();
209 
210  ASSERT_EQ(NodeStatus::RUNNING, state);
211  ASSERT_EQ(NodeStatus::FAILURE, condition.status());
212  ASSERT_EQ(NodeStatus::RUNNING, action.status());
213 }
214 
216 {
217  BT::NodeStatus state = root.executeTick();
218 
219  ASSERT_EQ(NodeStatus::SUCCESS, state);
220  ASSERT_EQ(NodeStatus::IDLE, fal_conditions.status());
221  ASSERT_EQ(NodeStatus::IDLE, condition_1.status());
222  ASSERT_EQ(NodeStatus::IDLE, condition_2.status());
223  ASSERT_EQ(NodeStatus::IDLE, fal_actions.status());
224  ASSERT_EQ(NodeStatus::IDLE, action_1.status());
225  ASSERT_EQ(NodeStatus::IDLE, action_2.status());
226 }
227 
229 {
230  condition_1.setExpectedResult(NodeStatus::FAILURE);
231  BT::NodeStatus state = root.executeTick();
232 
233  ASSERT_EQ(NodeStatus::SUCCESS, state);
234  ASSERT_EQ(NodeStatus::IDLE, fal_conditions.status());
235  ASSERT_EQ(NodeStatus::IDLE, condition_1.status());
236  ASSERT_EQ(NodeStatus::IDLE, condition_2.status());
237  ASSERT_EQ(NodeStatus::IDLE, fal_actions.status());
238  ASSERT_EQ(NodeStatus::IDLE, action_1.status());
239  ASSERT_EQ(NodeStatus::IDLE, action_2.status());
240 }
241 
243 {
244  condition_1.setExpectedResult(NodeStatus::FAILURE);
245  condition_2.setExpectedResult(NodeStatus::FAILURE);
246  BT::NodeStatus state = root.executeTick();
247 
248  ASSERT_EQ(NodeStatus::RUNNING, state);
249  ASSERT_EQ(NodeStatus::FAILURE, fal_conditions.status());
250  ASSERT_EQ(NodeStatus::IDLE, condition_1.status());
251  ASSERT_EQ(NodeStatus::IDLE, condition_2.status());
252  ASSERT_EQ(NodeStatus::RUNNING, fal_actions.status());
253  ASSERT_EQ(NodeStatus::RUNNING, action_1.status());
254  ASSERT_EQ(NodeStatus::IDLE, action_2.status());
255 }
256 
258 {
259  condition_1.setExpectedResult(NodeStatus::FAILURE);
260  condition_2.setExpectedResult(NodeStatus::FAILURE);
261  BT::NodeStatus state = root.executeTick();
262 
263  condition_1.setExpectedResult(NodeStatus::SUCCESS);
264  state = root.executeTick();
265 
266  ASSERT_EQ(NodeStatus::RUNNING, state);
267  ASSERT_EQ(NodeStatus::FAILURE, fal_conditions.status());
268  ASSERT_EQ(NodeStatus::IDLE, condition_1.status());
269  ASSERT_EQ(NodeStatus::IDLE, condition_2.status());
270  ASSERT_EQ(NodeStatus::RUNNING, fal_actions.status());
271  ASSERT_EQ(NodeStatus::RUNNING, action_1.status());
272  ASSERT_EQ(NodeStatus::IDLE, action_2.status());
273 }
274 
276 {
277  condition_1.setExpectedResult(NodeStatus::FAILURE);
278  condition_2.setExpectedResult(NodeStatus::FAILURE);
279  BT::NodeStatus state = root.executeTick();
280 
281  condition_2.setExpectedResult(NodeStatus::SUCCESS);
282  state = root.executeTick();
283 
284  ASSERT_EQ(NodeStatus::RUNNING, state);
285  ASSERT_EQ(NodeStatus::FAILURE, fal_conditions.status());
286  ASSERT_EQ(NodeStatus::IDLE, condition_1.status());
287  ASSERT_EQ(NodeStatus::IDLE, condition_2.status());
288  ASSERT_EQ(NodeStatus::RUNNING, fal_actions.status());
289  ASSERT_EQ(NodeStatus::RUNNING, action_1.status());
290  ASSERT_EQ(NodeStatus::IDLE, action_2.status());
291 }
292 
294 {
295  action_1.setExpectedResult(NodeStatus::FAILURE);
296  action_2.setExpectedResult(NodeStatus::SUCCESS);
297  condition_1.setExpectedResult(NodeStatus::FAILURE);
298  condition_2.setExpectedResult(NodeStatus::FAILURE);
299 
300  BT::NodeStatus state = root.executeTick();
301 
302  state = root.executeTick();
303  std::this_thread::sleep_for(std::chrono::milliseconds(500));
304  state = root.executeTick();
305 
306  ASSERT_EQ(NodeStatus::RUNNING, state);
307  ASSERT_EQ(NodeStatus::FAILURE, fal_conditions.status());
308  ASSERT_EQ(NodeStatus::IDLE, condition_1.status());
309  ASSERT_EQ(NodeStatus::IDLE, condition_2.status());
310  ASSERT_EQ(NodeStatus::RUNNING, fal_actions.status());
311  ASSERT_EQ(NodeStatus::FAILURE, action_1.status());
312  ASSERT_EQ(NodeStatus::RUNNING, action_2.status());
313 }
314 
315 
316 TEST(FallbackAndRetry, FallbackAndRetry)
317 {
318  using namespace BT;
319  static const char* xml_text = R"(
320 
321  <root main_tree_to_execute="BehaviorTree">
322  <BehaviorTree ID="BehaviorTree">
323  <RetryUntilSuccessful num_attempts="2">
324  <Fallback>
325  <AsyncActionTest name="first"/>
326  <ForceFailure>
327  <AsyncActionTest name="second"/>
328  </ForceFailure>
329  </Fallback>
330  </RetryUntilSuccessful>
331  </BehaviorTree>
332  </root>
333  )";
334 
335  BehaviorTreeFactory factory;
336  factory.registerNodeType<AsyncActionTest>("AsyncActionTest");
337 
338  auto tree = factory.createTreeFromText(xml_text);
339 
340  std::vector<AsyncActionTest*> async;
341 
342  for(auto node: tree.nodes) {
343  if(auto async_node = dynamic_cast<AsyncActionTest*>(node.get()) )
344  {
345  async.push_back(async_node);
346  }
347  }
348 
349  ASSERT_EQ(async.size(), 2);
350  async[0]->setExpectedResult(NodeStatus::FAILURE);
351  async[1]->setExpectedResult(NodeStatus::SUCCESS);
352 
353  auto res = tree.tickRootWhileRunning();
354 
355  ASSERT_EQ(async[0]->failureCount(), 2);
356  ASSERT_EQ(async[0]->successCount(), 0);
357 
358  ASSERT_EQ(async[1]->failureCount(), 0);
359  ASSERT_EQ(async[1]->successCount(), 2);
360 
361  ASSERT_EQ(NodeStatus::FAILURE, res);
362 }
363 
BT::AsyncActionTest action_1
BT::AsyncActionTest action
void registerNodeType(const std::string &ID)
Definition: bt_factory.h:364
BT::ConditionTestNode condition
BT::ConditionTestNode condition
NodeStatus status() const
Definition: tree_node.cpp:84
BT::AsyncActionTest action_2
BT::ReactiveFallback root
static const char * xml_text
BT::ConditionTestNode condition_1
BT::ConditionTestNode condition_2
void setExpectedResult(NodeStatus res)
The BehaviorTreeFactory is used to create instances of a TreeNode at run-time.
Definition: bt_factory.h:251
TEST(FallbackAndRetry, FallbackAndRetry)
BT::AsyncActionTest action_1
Tree createTreeFromText(const std::string &text, Blackboard::Ptr blackboard=Blackboard::create())
Definition: bt_factory.cpp:278
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: ...
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:32
The FallbackNode is used to try different strategies, until one succeeds. If any child returns RUNNIN...
Definition: fallback_node.h:32
BT::ConditionTestNode condition_1
TEST_F(SimpleFallbackTest, ConditionTrue)


behaviortree_cpp_v3
Author(s): Michele Colledanchise, Davide Faconti
autogenerated on Mon Jul 3 2023 02:50:14