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"), condition("condition"), action("action", milliseconds(100))
29  {
32  }
34  {}
35 };
36 
37 struct ReactiveFallbackTest : testing::Test
38 {
43 
45  : root("root_first")
46  , condition_1("condition_1")
47  , condition_2("condition_2")
48  , action_1("action_1", milliseconds(100))
49  {
53  }
55  {}
56 };
57 
58 struct SimpleFallbackWithMemoryTest : testing::Test
59 {
63 
65  : root("root_sequence"), action("action", milliseconds(100)), condition("condition")
66  {
69  }
71  {}
72 };
73 
74 struct ComplexFallbackWithMemoryTest : testing::Test
75 {
77 
80 
83 
86 
88  : root("root_fallback")
89  , action_1("action_1", milliseconds(100))
90  , action_2("action_2", milliseconds(100))
91  , condition_1("condition_1")
92  , condition_2("condition_2")
93  , fal_conditions("fallback_conditions")
94  , fal_actions("fallback_actions")
95  {
97  {
100  }
102  {
105  }
106  }
108  {}
109 };
110 
111 /****************TESTS START HERE***************************/
112 
113 TEST_F(SimpleFallbackTest, ConditionTrue)
114 {
115  // Ticking the root node
116  condition.setExpectedResult(NodeStatus::SUCCESS);
117  BT::NodeStatus state = root.executeTick();
118 
119  ASSERT_EQ(NodeStatus::SUCCESS, state);
120  ASSERT_EQ(NodeStatus::IDLE, condition.status());
121  ASSERT_EQ(NodeStatus::IDLE, action.status());
122 }
123 
124 TEST_F(SimpleFallbackTest, ConditionChangeWhileRunning)
125 {
127 
128  condition.setExpectedResult(NodeStatus::FAILURE);
129  state = root.executeTick();
130 
131  ASSERT_EQ(NodeStatus::RUNNING, state);
132  ASSERT_EQ(NodeStatus::FAILURE, condition.status());
133  ASSERT_EQ(NodeStatus::RUNNING, action.status());
134 
135  condition.setExpectedResult(NodeStatus::SUCCESS);
136  state = root.executeTick();
137 
138  ASSERT_EQ(NodeStatus::RUNNING, state);
139  ASSERT_EQ(NodeStatus::FAILURE, condition.status());
140  ASSERT_EQ(NodeStatus::RUNNING, action.status());
141 }
142 
143 TEST_F(ReactiveFallbackTest, Condition1ToTrue)
144 {
145  condition_1.setExpectedResult(NodeStatus::FAILURE);
146  condition_2.setExpectedResult(NodeStatus::FAILURE);
147 
148  BT::NodeStatus state = root.executeTick();
149 
150  ASSERT_EQ(NodeStatus::RUNNING, state);
151  ASSERT_EQ(NodeStatus::IDLE, condition_1.status());
152  ASSERT_EQ(NodeStatus::IDLE, condition_2.status());
153  ASSERT_EQ(NodeStatus::RUNNING, action_1.status());
154 
155  condition_1.setExpectedResult(NodeStatus::SUCCESS);
156 
157  state = root.executeTick();
158 
159  ASSERT_EQ(NodeStatus::SUCCESS, state);
160  ASSERT_EQ(NodeStatus::IDLE, condition_1.status());
161  ASSERT_EQ(NodeStatus::IDLE, condition_2.status());
162  ASSERT_EQ(NodeStatus::IDLE, action_1.status());
163 }
164 
165 TEST_F(ReactiveFallbackTest, Condition2ToTrue)
166 {
167  condition_1.setExpectedResult(NodeStatus::FAILURE);
168  condition_2.setExpectedResult(NodeStatus::FAILURE);
169 
170  BT::NodeStatus state = root.executeTick();
171 
172  ASSERT_EQ(NodeStatus::RUNNING, state);
173  ASSERT_EQ(NodeStatus::IDLE, condition_1.status());
174  ASSERT_EQ(NodeStatus::IDLE, condition_2.status());
175  ASSERT_EQ(NodeStatus::RUNNING, action_1.status());
176 
177  condition_2.setExpectedResult(NodeStatus::SUCCESS);
178 
179  state = root.executeTick();
180 
181  ASSERT_EQ(NodeStatus::SUCCESS, state);
182  ASSERT_EQ(NodeStatus::IDLE, condition_1.status());
183  ASSERT_EQ(NodeStatus::IDLE, condition_2.status());
184  ASSERT_EQ(NodeStatus::IDLE, action_1.status());
185 }
186 
188 {
189  condition.setExpectedResult(NodeStatus::FAILURE);
190  BT::NodeStatus state = root.executeTick();
191 
192  ASSERT_EQ(NodeStatus::RUNNING, state);
193  ASSERT_EQ(NodeStatus::FAILURE, condition.status());
194  ASSERT_EQ(NodeStatus::RUNNING, action.status());
195 }
196 
198 {
199  condition.setExpectedResult(NodeStatus::FAILURE);
200  BT::NodeStatus state = root.executeTick();
201 
202  ASSERT_EQ(NodeStatus::RUNNING, state);
203  ASSERT_EQ(NodeStatus::FAILURE, condition.status());
204  ASSERT_EQ(NodeStatus::RUNNING, action.status());
205 
206  condition.setExpectedResult(NodeStatus::SUCCESS);
207  state = root.executeTick();
208 
209  ASSERT_EQ(NodeStatus::RUNNING, state);
210  ASSERT_EQ(NodeStatus::FAILURE, condition.status());
211  ASSERT_EQ(NodeStatus::RUNNING, action.status());
212 }
213 
215 {
216  BT::NodeStatus state = root.executeTick();
217 
218  ASSERT_EQ(NodeStatus::SUCCESS, state);
219  ASSERT_EQ(NodeStatus::IDLE, fal_conditions.status());
220  ASSERT_EQ(NodeStatus::IDLE, condition_1.status());
221  ASSERT_EQ(NodeStatus::IDLE, condition_2.status());
222  ASSERT_EQ(NodeStatus::IDLE, fal_actions.status());
223  ASSERT_EQ(NodeStatus::IDLE, action_1.status());
224  ASSERT_EQ(NodeStatus::IDLE, action_2.status());
225 }
226 
228 {
229  condition_1.setExpectedResult(NodeStatus::FAILURE);
230  BT::NodeStatus state = root.executeTick();
231 
232  ASSERT_EQ(NodeStatus::SUCCESS, state);
233  ASSERT_EQ(NodeStatus::IDLE, fal_conditions.status());
234  ASSERT_EQ(NodeStatus::IDLE, condition_1.status());
235  ASSERT_EQ(NodeStatus::IDLE, condition_2.status());
236  ASSERT_EQ(NodeStatus::IDLE, fal_actions.status());
237  ASSERT_EQ(NodeStatus::IDLE, action_1.status());
238  ASSERT_EQ(NodeStatus::IDLE, action_2.status());
239 }
240 
242 {
243  condition_1.setExpectedResult(NodeStatus::FAILURE);
244  condition_2.setExpectedResult(NodeStatus::FAILURE);
245  BT::NodeStatus state = root.executeTick();
246 
247  ASSERT_EQ(NodeStatus::RUNNING, state);
248  ASSERT_EQ(NodeStatus::FAILURE, fal_conditions.status());
249  ASSERT_EQ(NodeStatus::IDLE, condition_1.status());
250  ASSERT_EQ(NodeStatus::IDLE, condition_2.status());
251  ASSERT_EQ(NodeStatus::RUNNING, fal_actions.status());
252  ASSERT_EQ(NodeStatus::RUNNING, action_1.status());
253  ASSERT_EQ(NodeStatus::IDLE, action_2.status());
254 }
255 
257 {
258  condition_1.setExpectedResult(NodeStatus::FAILURE);
259  condition_2.setExpectedResult(NodeStatus::FAILURE);
260  BT::NodeStatus state = root.executeTick();
261 
262  condition_1.setExpectedResult(NodeStatus::SUCCESS);
263  state = root.executeTick();
264 
265  ASSERT_EQ(NodeStatus::RUNNING, state);
266  ASSERT_EQ(NodeStatus::FAILURE, fal_conditions.status());
267  ASSERT_EQ(NodeStatus::IDLE, condition_1.status());
268  ASSERT_EQ(NodeStatus::IDLE, condition_2.status());
269  ASSERT_EQ(NodeStatus::RUNNING, fal_actions.status());
270  ASSERT_EQ(NodeStatus::RUNNING, action_1.status());
271  ASSERT_EQ(NodeStatus::IDLE, action_2.status());
272 }
273 
275 {
276  condition_1.setExpectedResult(NodeStatus::FAILURE);
277  condition_2.setExpectedResult(NodeStatus::FAILURE);
278  BT::NodeStatus state = root.executeTick();
279 
280  condition_2.setExpectedResult(NodeStatus::SUCCESS);
281  state = root.executeTick();
282 
283  ASSERT_EQ(NodeStatus::RUNNING, state);
284  ASSERT_EQ(NodeStatus::FAILURE, fal_conditions.status());
285  ASSERT_EQ(NodeStatus::IDLE, condition_1.status());
286  ASSERT_EQ(NodeStatus::IDLE, condition_2.status());
287  ASSERT_EQ(NodeStatus::RUNNING, fal_actions.status());
288  ASSERT_EQ(NodeStatus::RUNNING, action_1.status());
289  ASSERT_EQ(NodeStatus::IDLE, action_2.status());
290 }
291 
293 {
294  action_1.setExpectedResult(NodeStatus::FAILURE);
295  action_2.setExpectedResult(NodeStatus::SUCCESS);
296  condition_1.setExpectedResult(NodeStatus::FAILURE);
297  condition_2.setExpectedResult(NodeStatus::FAILURE);
298 
299  BT::NodeStatus state = root.executeTick();
300 
301  state = root.executeTick();
302  std::this_thread::sleep_for(std::chrono::milliseconds(500));
303  state = root.executeTick();
304 
305  ASSERT_EQ(NodeStatus::RUNNING, state);
306  ASSERT_EQ(NodeStatus::FAILURE, fal_conditions.status());
307  ASSERT_EQ(NodeStatus::IDLE, condition_1.status());
308  ASSERT_EQ(NodeStatus::IDLE, condition_2.status());
309  ASSERT_EQ(NodeStatus::RUNNING, fal_actions.status());
310  ASSERT_EQ(NodeStatus::FAILURE, action_1.status());
311  ASSERT_EQ(NodeStatus::RUNNING, action_2.status());
312 }
ReactiveFallbackTest::condition_1
BT::ConditionTestNode condition_1
Definition: gtest_fallback.cpp:40
SimpleFallbackTest::SimpleFallbackTest
SimpleFallbackTest()
Definition: gtest_fallback.cpp:27
SimpleFallbackTest::condition
BT::ConditionTestNode condition
Definition: gtest_fallback.cpp:24
ComplexFallbackWithMemoryTest::fal_conditions
BT::FallbackNode fal_conditions
Definition: gtest_fallback.cpp:84
ComplexFallbackWithMemoryTest::action_1
BT::AsyncActionTest action_1
Definition: gtest_fallback.cpp:78
SimpleFallbackWithMemoryTest::condition
BT::ConditionTestNode condition
Definition: gtest_fallback.cpp:62
BT::AsyncActionTest
Definition: action_test_node.h:32
ReactiveFallbackTest
Definition: gtest_fallback.cpp:37
ComplexFallbackWithMemoryTest::ComplexFallbackWithMemoryTest
ComplexFallbackWithMemoryTest()
Definition: gtest_fallback.cpp:87
SimpleFallbackWithMemoryTest::root
BT::FallbackNode root
Definition: gtest_fallback.cpp:60
ComplexFallbackWithMemoryTest::condition_1
BT::ConditionTestNode condition_1
Definition: gtest_fallback.cpp:81
ComplexFallbackWithMemoryTest::action_2
BT::AsyncActionTest action_2
Definition: gtest_fallback.cpp:79
ReactiveFallbackTest::~ReactiveFallbackTest
~ReactiveFallbackTest() override
Definition: gtest_fallback.cpp:54
condition_test_node.h
ComplexFallbackWithMemoryTest::~ComplexFallbackWithMemoryTest
~ComplexFallbackWithMemoryTest() override
Definition: gtest_fallback.cpp:107
SimpleFallbackTest::root
BT::FallbackNode root
Definition: gtest_fallback.cpp:23
ComplexFallbackWithMemoryTest
Definition: gtest_fallback.cpp:74
ComplexFallbackWithMemoryTest::condition_2
BT::ConditionTestNode condition_2
Definition: gtest_fallback.cpp:82
SimpleFallbackWithMemoryTest
Definition: gtest_fallback.cpp:58
ReactiveFallbackTest::condition_2
BT::ConditionTestNode condition_2
Definition: gtest_fallback.cpp:41
behavior_tree.h
SimpleFallbackWithMemoryTest::~SimpleFallbackWithMemoryTest
~SimpleFallbackWithMemoryTest() override
Definition: gtest_fallback.cpp:70
ReactiveFallbackTest::action_1
BT::AsyncActionTest action_1
Definition: gtest_fallback.cpp:42
TEST_F
TEST_F(SimpleFallbackTest, ConditionTrue)
Definition: gtest_fallback.cpp:113
BT::FallbackNode
The FallbackNode is used to try different strategies, until one succeeds. If any child returns RUNNIN...
Definition: fallback_node.h:32
SimpleFallbackTest::action
BT::AsyncActionTest action
Definition: gtest_fallback.cpp:25
SimpleFallbackTest
Definition: gtest_fallback.cpp:21
ReactiveFallbackTest::root
BT::ReactiveFallback root
Definition: gtest_fallback.cpp:39
SimpleFallbackWithMemoryTest::SimpleFallbackWithMemoryTest
SimpleFallbackWithMemoryTest()
Definition: gtest_fallback.cpp:64
ReactiveFallbackTest::ReactiveFallbackTest
ReactiveFallbackTest()
Definition: gtest_fallback.cpp:44
action_test_node.h
BT::NodeStatus::IDLE
@ IDLE
BT::ConditionTestNode
Definition: condition_test_node.h:8
SimpleFallbackTest::~SimpleFallbackTest
~SimpleFallbackTest() override
Definition: gtest_fallback.cpp:33
ComplexFallbackWithMemoryTest::root
BT::FallbackNode root
Definition: gtest_fallback.cpp:76
BT::ControlNode::addChild
void addChild(TreeNode *child)
The method used to add nodes to the children vector.
Definition: control_node.cpp:22
BT::ReactiveFallback
The ReactiveFallback is similar to a ParallelNode. All the children are ticked from first to last:
Definition: reactive_fallback.h:33
BT::NodeStatus
NodeStatus
Definition: basic_types.h:33
ComplexFallbackWithMemoryTest::fal_actions
BT::FallbackNode fal_actions
Definition: gtest_fallback.cpp:85
SimpleFallbackWithMemoryTest::action
BT::AsyncActionTest action
Definition: gtest_fallback.cpp:61


behaviortree_cpp_v4
Author(s): Davide Faconti
autogenerated on Fri Jun 28 2024 02:20:07