1 #include <gtest/gtest.h>
9 using std::chrono::milliseconds;
13 <root BTCPP_format="4" >
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"/>
39 std::unique_ptr<Switch2>
root;
47 :
action_1(
"action_1", milliseconds(200))
48 ,
action_42(
"action_42", milliseconds(200))
49 ,
action_def(
"action_default", milliseconds(200))
52 input.insert(std::make_pair(
"variable",
"{my_var}"));
53 input.insert(std::make_pair(
"case_1",
"1"));
54 input.insert(std::make_pair(
"case_2",
"42"));
76 ASSERT_EQ(NodeStatus::IDLE, action_1.status());
77 ASSERT_EQ(NodeStatus::IDLE, action_42.status());
78 ASSERT_EQ(NodeStatus::RUNNING, action_def.status());
79 ASSERT_EQ(NodeStatus::RUNNING, state);
81 std::this_thread::sleep_for(milliseconds(300));
82 state = root->executeTick();
84 ASSERT_EQ(NodeStatus::IDLE, action_1.status());
85 ASSERT_EQ(NodeStatus::IDLE, action_42.status());
86 ASSERT_EQ(NodeStatus::IDLE, action_def.status());
87 ASSERT_EQ(NodeStatus::SUCCESS, state);
92 bb->set(
"my_var",
"1");
95 ASSERT_EQ(NodeStatus::RUNNING, action_1.status());
96 ASSERT_EQ(NodeStatus::IDLE, action_42.status());
97 ASSERT_EQ(NodeStatus::IDLE, action_def.status());
98 ASSERT_EQ(NodeStatus::RUNNING, state);
100 std::this_thread::sleep_for(milliseconds(300));
101 state = root->executeTick();
103 ASSERT_EQ(NodeStatus::IDLE, action_1.status());
104 ASSERT_EQ(NodeStatus::IDLE, action_42.status());
105 ASSERT_EQ(NodeStatus::IDLE, action_def.status());
106 ASSERT_EQ(NodeStatus::SUCCESS, state);
111 bb->set(
"my_var",
"42");
114 ASSERT_EQ(NodeStatus::IDLE, action_1.status());
115 ASSERT_EQ(NodeStatus::RUNNING, action_42.status());
116 ASSERT_EQ(NodeStatus::IDLE, action_def.status());
117 ASSERT_EQ(NodeStatus::RUNNING, state);
119 std::this_thread::sleep_for(milliseconds(300));
120 state = root->executeTick();
122 ASSERT_EQ(NodeStatus::IDLE, action_1.status());
123 ASSERT_EQ(NodeStatus::IDLE, action_42.status());
124 ASSERT_EQ(NodeStatus::IDLE, action_def.status());
125 ASSERT_EQ(NodeStatus::SUCCESS, state);
130 bb->set(
"my_var",
"none");
133 ASSERT_EQ(NodeStatus::IDLE, action_1.status());
134 ASSERT_EQ(NodeStatus::IDLE, action_42.status());
135 ASSERT_EQ(NodeStatus::RUNNING, action_def.status());
136 ASSERT_EQ(NodeStatus::RUNNING, state);
138 std::this_thread::sleep_for(milliseconds(300));
139 state = root->executeTick();
141 ASSERT_EQ(NodeStatus::IDLE, action_1.status());
142 ASSERT_EQ(NodeStatus::IDLE, action_42.status());
143 ASSERT_EQ(NodeStatus::IDLE, action_def.status());
144 ASSERT_EQ(NodeStatus::SUCCESS, state);
149 bb->set(
"my_var",
"1");
152 ASSERT_EQ(NodeStatus::RUNNING, action_1.status());
153 ASSERT_EQ(NodeStatus::IDLE, action_42.status());
154 ASSERT_EQ(NodeStatus::IDLE, action_def.status());
155 ASSERT_EQ(NodeStatus::RUNNING, state);
157 std::this_thread::sleep_for(milliseconds(20));
158 state = root->executeTick();
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, state);
166 std::this_thread::sleep_for(milliseconds(20));
167 bb->set(
"my_var",
"");
168 std::this_thread::sleep_for(milliseconds(20));
169 ASSERT_EQ(NodeStatus::RUNNING, action_1.status());
170 ASSERT_EQ(NodeStatus::IDLE, action_42.status());
171 ASSERT_EQ(NodeStatus::IDLE, action_def.status());
172 ASSERT_EQ(NodeStatus::RUNNING, root->status());
174 std::this_thread::sleep_for(milliseconds(20));
175 state = root->executeTick();
176 ASSERT_EQ(NodeStatus::IDLE, action_1.status());
177 ASSERT_EQ(NodeStatus::IDLE, action_42.status());
178 ASSERT_EQ(NodeStatus::RUNNING, action_def.status());
179 ASSERT_EQ(NodeStatus::RUNNING, state);
181 std::this_thread::sleep_for(milliseconds(300));
182 state = root->executeTick();
184 ASSERT_EQ(NodeStatus::IDLE, action_1.status());
185 ASSERT_EQ(NodeStatus::IDLE, action_42.status());
186 ASSERT_EQ(NodeStatus::IDLE, action_def.status());
187 ASSERT_EQ(NodeStatus::SUCCESS, root->status());
192 bb->set(
"my_var",
"1");
195 ASSERT_EQ(NodeStatus::RUNNING, action_1.status());
196 ASSERT_EQ(NodeStatus::IDLE, action_42.status());
197 ASSERT_EQ(NodeStatus::IDLE, action_def.status());
198 ASSERT_EQ(NodeStatus::RUNNING, state);
200 bb->set(
"my_var",
"42");
201 std::this_thread::sleep_for(milliseconds(20));
202 state = root->executeTick();
203 ASSERT_EQ(NodeStatus::IDLE, action_1.status());
204 ASSERT_EQ(NodeStatus::RUNNING, action_42.status());
205 ASSERT_EQ(NodeStatus::IDLE, action_def.status());
206 ASSERT_EQ(NodeStatus::RUNNING, state);
208 std::this_thread::sleep_for(milliseconds(300));
209 state = root->executeTick();
211 ASSERT_EQ(NodeStatus::IDLE, action_1.status());
212 ASSERT_EQ(NodeStatus::IDLE, action_42.status());
213 ASSERT_EQ(NodeStatus::IDLE, action_def.status());
214 ASSERT_EQ(NodeStatus::SUCCESS, root->status());
219 bb->set(
"my_var",
"1");
222 action_1.setExpectedResult(NodeStatus::FAILURE);
224 ASSERT_EQ(NodeStatus::RUNNING, action_1.status());
225 ASSERT_EQ(NodeStatus::IDLE, action_42.status());
226 ASSERT_EQ(NodeStatus::IDLE, action_def.status());
227 ASSERT_EQ(NodeStatus::RUNNING, state);
229 std::this_thread::sleep_for(milliseconds(300));
230 state = root->executeTick();
232 ASSERT_EQ(NodeStatus::FAILURE, state);
233 ASSERT_EQ(NodeStatus::IDLE, action_1.status());
234 ASSERT_EQ(NodeStatus::IDLE, action_42.status());
235 ASSERT_EQ(NodeStatus::IDLE, action_def.status());