13 #include <gtest/gtest.h>
19 using std::chrono::milliseconds;
48 ,
action_1(
"action_1", milliseconds(100))
88 :
root(
"root_fallback")
89 ,
action_1(
"action_1", milliseconds(100))
90 ,
action_2(
"action_2", milliseconds(100))
116 condition.setExpectedResult(NodeStatus::SUCCESS);
119 ASSERT_EQ(NodeStatus::SUCCESS, state);
120 ASSERT_EQ(NodeStatus::IDLE, condition.status());
121 ASSERT_EQ(NodeStatus::IDLE, action.status());
128 condition.setExpectedResult(NodeStatus::FAILURE);
129 state = root.executeTick();
131 ASSERT_EQ(NodeStatus::RUNNING, state);
132 ASSERT_EQ(NodeStatus::FAILURE, condition.status());
133 ASSERT_EQ(NodeStatus::RUNNING, action.status());
135 condition.setExpectedResult(NodeStatus::SUCCESS);
136 state = root.executeTick();
138 ASSERT_EQ(NodeStatus::RUNNING, state);
139 ASSERT_EQ(NodeStatus::FAILURE, condition.status());
140 ASSERT_EQ(NodeStatus::RUNNING, action.status());
145 condition_1.setExpectedResult(NodeStatus::FAILURE);
146 condition_2.setExpectedResult(NodeStatus::FAILURE);
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());
155 condition_1.setExpectedResult(NodeStatus::SUCCESS);
157 state = root.executeTick();
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());
167 condition_1.setExpectedResult(NodeStatus::FAILURE);
168 condition_2.setExpectedResult(NodeStatus::FAILURE);
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());
177 condition_2.setExpectedResult(NodeStatus::SUCCESS);
179 state = root.executeTick();
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());
189 condition.setExpectedResult(NodeStatus::FAILURE);
192 ASSERT_EQ(NodeStatus::RUNNING, state);
193 ASSERT_EQ(NodeStatus::FAILURE, condition.status());
194 ASSERT_EQ(NodeStatus::RUNNING, action.status());
199 condition.setExpectedResult(NodeStatus::FAILURE);
202 ASSERT_EQ(NodeStatus::RUNNING, state);
203 ASSERT_EQ(NodeStatus::FAILURE, condition.status());
204 ASSERT_EQ(NodeStatus::RUNNING, action.status());
206 condition.setExpectedResult(NodeStatus::SUCCESS);
207 state = root.executeTick();
209 ASSERT_EQ(NodeStatus::RUNNING, state);
210 ASSERT_EQ(NodeStatus::FAILURE, condition.status());
211 ASSERT_EQ(NodeStatus::RUNNING, action.status());
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());
229 condition_1.setExpectedResult(NodeStatus::FAILURE);
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());
243 condition_1.setExpectedResult(NodeStatus::FAILURE);
244 condition_2.setExpectedResult(NodeStatus::FAILURE);
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());
258 condition_1.setExpectedResult(NodeStatus::FAILURE);
259 condition_2.setExpectedResult(NodeStatus::FAILURE);
262 condition_1.setExpectedResult(NodeStatus::SUCCESS);
263 state = root.executeTick();
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());
276 condition_1.setExpectedResult(NodeStatus::FAILURE);
277 condition_2.setExpectedResult(NodeStatus::FAILURE);
280 condition_2.setExpectedResult(NodeStatus::SUCCESS);
281 state = root.executeTick();
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());
294 action_1.setExpectedResult(NodeStatus::FAILURE);
295 action_2.setExpectedResult(NodeStatus::SUCCESS);
296 condition_1.setExpectedResult(NodeStatus::FAILURE);
297 condition_2.setExpectedResult(NodeStatus::FAILURE);
301 state = root.executeTick();
302 std::this_thread::sleep_for(std::chrono::milliseconds(500));
303 state = root.executeTick();
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());