1 #include <gtest/gtest.h>
9 using std::chrono::milliseconds;
13 <root main_tree_to_execute = "MainTree" >
15 <BehaviorTree ID="MainTree">
16 <Switch3 name="simple_switch" variable="{my_var}" case_1="1" case_2="42 case_3="666" >
17 <AsyncActionTest name="action_1"/>
18 <AsyncActionTest name="action_42"/>
19 <AsyncActionTest name="action_666"/>
20 <AsyncActionTest name="action_default"/>
29 std::unique_ptr<Switch2>
root;
37 action_1(
"action_1", milliseconds(100)),
38 action_42(
"action_42", milliseconds(100)),
39 action_def(
"action_default", milliseconds(100))
42 input.insert(std::make_pair(
"variable",
"{my_var}"));
43 input.insert(std::make_pair(
"case_1",
"1"));
44 input.insert(std::make_pair(
"case_2",
"42"));
66 ASSERT_EQ(NodeStatus::IDLE, action_1.status());
67 ASSERT_EQ(NodeStatus::IDLE, action_42.status());
68 ASSERT_EQ(NodeStatus::RUNNING, action_def.status());
69 ASSERT_EQ(NodeStatus::RUNNING, state);
71 std::this_thread::sleep_for(milliseconds(110));
72 state = root->executeTick();
74 ASSERT_EQ(NodeStatus::IDLE, action_1.status());
75 ASSERT_EQ(NodeStatus::IDLE, action_42.status());
76 ASSERT_EQ(NodeStatus::IDLE, action_def.status());
77 ASSERT_EQ(NodeStatus::SUCCESS, state);
82 bb->set(
"my_var",
"1");
85 ASSERT_EQ(NodeStatus::RUNNING, action_1.status());
86 ASSERT_EQ(NodeStatus::IDLE, action_42.status());
87 ASSERT_EQ(NodeStatus::IDLE, action_def.status());
88 ASSERT_EQ(NodeStatus::RUNNING, state);
90 std::this_thread::sleep_for(milliseconds(110));
91 state = root->executeTick();
93 ASSERT_EQ(NodeStatus::IDLE, action_1.status());
94 ASSERT_EQ(NodeStatus::IDLE, action_42.status());
95 ASSERT_EQ(NodeStatus::IDLE, action_def.status());
96 ASSERT_EQ(NodeStatus::SUCCESS, state);
101 bb->set(
"my_var",
"42");
104 ASSERT_EQ(NodeStatus::IDLE, action_1.status());
105 ASSERT_EQ(NodeStatus::RUNNING, action_42.status());
106 ASSERT_EQ(NodeStatus::IDLE, action_def.status());
107 ASSERT_EQ(NodeStatus::RUNNING, state);
109 std::this_thread::sleep_for(milliseconds(110));
110 state = root->executeTick();
112 ASSERT_EQ(NodeStatus::IDLE, action_1.status());
113 ASSERT_EQ(NodeStatus::IDLE, action_42.status());
114 ASSERT_EQ(NodeStatus::IDLE, action_def.status());
115 ASSERT_EQ(NodeStatus::SUCCESS, state);
120 bb->set(
"my_var",
"none");
123 ASSERT_EQ(NodeStatus::IDLE, action_1.status());
124 ASSERT_EQ(NodeStatus::IDLE, action_42.status());
125 ASSERT_EQ(NodeStatus::RUNNING, action_def.status());
126 ASSERT_EQ(NodeStatus::RUNNING, state);
128 std::this_thread::sleep_for(milliseconds(110));
129 state = root->executeTick();
131 ASSERT_EQ(NodeStatus::IDLE, action_1.status());
132 ASSERT_EQ(NodeStatus::IDLE, action_42.status());
133 ASSERT_EQ(NodeStatus::IDLE, action_def.status());
134 ASSERT_EQ(NodeStatus::SUCCESS, state);
139 bb->set(
"my_var",
"1");
142 ASSERT_EQ(NodeStatus::RUNNING, action_1.status());
143 ASSERT_EQ(NodeStatus::IDLE, action_42.status());
144 ASSERT_EQ(NodeStatus::IDLE, action_def.status());
145 ASSERT_EQ(NodeStatus::RUNNING, state);
147 std::this_thread::sleep_for(milliseconds(10));
148 state = root->executeTick();
149 ASSERT_EQ(NodeStatus::RUNNING, action_1.status());
150 ASSERT_EQ(NodeStatus::IDLE, action_42.status());
151 ASSERT_EQ(NodeStatus::IDLE, action_def.status());
152 ASSERT_EQ(NodeStatus::RUNNING, state);
156 std::this_thread::sleep_for(milliseconds(10));
157 bb->set(
"my_var",
"");
158 std::this_thread::sleep_for(milliseconds(10));
159 ASSERT_EQ(NodeStatus::RUNNING, action_1.status());
160 ASSERT_EQ(NodeStatus::IDLE, action_42.status());
161 ASSERT_EQ(NodeStatus::IDLE, action_def.status());
162 ASSERT_EQ(NodeStatus::RUNNING, root->status());
164 std::this_thread::sleep_for(milliseconds(10));
165 state = root->executeTick();
166 ASSERT_EQ(NodeStatus::IDLE, action_1.status());
167 ASSERT_EQ(NodeStatus::IDLE, action_42.status());
168 ASSERT_EQ(NodeStatus::RUNNING, action_def.status());
169 ASSERT_EQ(NodeStatus::RUNNING, state);
171 std::this_thread::sleep_for(milliseconds(110));
172 state = root->executeTick();
174 ASSERT_EQ(NodeStatus::IDLE, action_1.status());
175 ASSERT_EQ(NodeStatus::IDLE, action_42.status());
176 ASSERT_EQ(NodeStatus::IDLE, action_def.status());
177 ASSERT_EQ(NodeStatus::SUCCESS, root->status());
182 bb->set(
"my_var",
"1");
185 ASSERT_EQ(NodeStatus::RUNNING, action_1.status());
186 ASSERT_EQ(NodeStatus::IDLE, action_42.status());
187 ASSERT_EQ(NodeStatus::IDLE, action_def.status());
188 ASSERT_EQ(NodeStatus::RUNNING, state);
190 bb->set(
"my_var",
"42");
191 std::this_thread::sleep_for(milliseconds(10));
192 state = root->executeTick();
193 ASSERT_EQ(NodeStatus::IDLE, action_1.status());
194 ASSERT_EQ(NodeStatus::RUNNING, action_42.status());
195 ASSERT_EQ(NodeStatus::IDLE, action_def.status());
196 ASSERT_EQ(NodeStatus::RUNNING, state);
198 std::this_thread::sleep_for(milliseconds(110));
199 state = root->executeTick();
201 ASSERT_EQ(NodeStatus::IDLE, action_1.status());
202 ASSERT_EQ(NodeStatus::IDLE, action_42.status());
203 ASSERT_EQ(NodeStatus::IDLE, action_def.status());
204 ASSERT_EQ(NodeStatus::SUCCESS, root->status());
209 bb->set(
"my_var",
"1");
212 action_1.setExpectedResult(NodeStatus::FAILURE);
214 ASSERT_EQ(NodeStatus::RUNNING, action_1.status());
215 ASSERT_EQ(NodeStatus::IDLE, action_42.status());
216 ASSERT_EQ(NodeStatus::IDLE, action_def.status());
217 ASSERT_EQ(NodeStatus::RUNNING, state);
219 std::this_thread::sleep_for(milliseconds(110));
220 state = root->executeTick();
222 ASSERT_EQ(NodeStatus::FAILURE, state);
223 ASSERT_EQ(NodeStatus::IDLE, action_1.status());
224 ASSERT_EQ(NodeStatus::IDLE, action_42.status());
225 ASSERT_EQ(NodeStatus::IDLE, action_def.status());