13 #include <gtest/gtest.h> 19 using std::chrono::milliseconds;
31 : root(
"root_parallel", 4)
32 , action_1(
"action_1", milliseconds(100) )
33 , condition_1(
"condition_1")
34 , action_2(
"action_2", milliseconds(300))
35 , condition_2(
"condition_2")
64 : parallel_root(
"root", 2)
65 , parallel_left(
"par1", 3)
66 , parallel_right(
"par2", 1)
67 , action_L1(
"action_1", milliseconds(100) )
68 , condition_L1(
"condition_1")
69 , action_L2(
"action_2", milliseconds(200) )
70 , condition_L2(
"condition_2")
71 , action_R(
"action_3", milliseconds(400) )
72 , condition_R(
"condition_3")
74 parallel_root.
addChild(¶llel_left);
76 parallel_left.
addChild(&condition_L1);
78 parallel_left.
addChild(&condition_L2);
81 parallel_root.
addChild(¶llel_right);
83 parallel_right.
addChild(&condition_R);
103 ASSERT_EQ(NodeStatus::RUNNING, state);
105 std::this_thread::sleep_for( milliseconds(200) );
112 ASSERT_EQ(NodeStatus::RUNNING, state);
114 std::this_thread::sleep_for( milliseconds(200) );
121 ASSERT_EQ(NodeStatus::SUCCESS, state);
136 ASSERT_EQ(NodeStatus::RUNNING, state);
138 std::this_thread::sleep_for( milliseconds(150) );
146 ASSERT_EQ(NodeStatus::SUCCESS, state);
158 ASSERT_EQ(NodeStatus::SUCCESS, state);
165 ASSERT_EQ(NodeStatus::RUNNING, parallel_left.status());
166 ASSERT_EQ(NodeStatus::SUCCESS, condition_L1.status());
167 ASSERT_EQ(NodeStatus::SUCCESS, condition_L2.status());
168 ASSERT_EQ(NodeStatus::RUNNING, action_L1.status());
169 ASSERT_EQ(NodeStatus::RUNNING, action_L2.status());
171 ASSERT_EQ(NodeStatus::SUCCESS, parallel_right.status());
172 ASSERT_EQ(NodeStatus::IDLE, condition_R.status());
173 ASSERT_EQ(NodeStatus::IDLE, action_R.status());
175 ASSERT_EQ(NodeStatus::RUNNING, state);
177 std::this_thread::sleep_for(milliseconds(200));
178 state = parallel_root.executeTick();
180 ASSERT_EQ(NodeStatus::IDLE, parallel_left.status());
181 ASSERT_EQ(NodeStatus::IDLE, condition_L1.status());
182 ASSERT_EQ(NodeStatus::IDLE, condition_L2.status());
183 ASSERT_EQ(NodeStatus::IDLE, action_L1.status());
184 ASSERT_EQ(NodeStatus::IDLE, action_L2.status());
186 ASSERT_EQ(NodeStatus::IDLE, parallel_right.status());
187 ASSERT_EQ(NodeStatus::IDLE, condition_R.status());
188 ASSERT_EQ(NodeStatus::IDLE, action_R.status());
190 ASSERT_EQ(NodeStatus::SUCCESS, state);
195 condition_R.setBoolean(
false);
200 ASSERT_EQ(NodeStatus::RUNNING, parallel_left.status());
201 ASSERT_EQ(NodeStatus::SUCCESS, condition_L1.status());
202 ASSERT_EQ(NodeStatus::SUCCESS, condition_L2.status());
203 ASSERT_EQ(NodeStatus::RUNNING, action_L1.status());
204 ASSERT_EQ(NodeStatus::RUNNING, action_L2.status());
206 ASSERT_EQ(NodeStatus::RUNNING, parallel_right.status());
207 ASSERT_EQ(NodeStatus::FAILURE, condition_R.status());
208 ASSERT_EQ(NodeStatus::RUNNING, action_R.status());
210 ASSERT_EQ(NodeStatus::RUNNING, state);
213 std::this_thread::sleep_for(milliseconds(500));
214 state = parallel_root.executeTick();
216 ASSERT_EQ(NodeStatus::IDLE, parallel_left.status());
217 ASSERT_EQ(NodeStatus::IDLE, condition_L1.status());
218 ASSERT_EQ(NodeStatus::IDLE, condition_L2.status());
219 ASSERT_EQ(NodeStatus::IDLE, action_L1.status());
220 ASSERT_EQ(NodeStatus::IDLE, action_L2.status());
222 ASSERT_EQ(NodeStatus::IDLE, parallel_right.status());
223 ASSERT_EQ(NodeStatus::IDLE, condition_R.status());
224 ASSERT_EQ(NodeStatus::IDLE, action_R.status());
226 ASSERT_EQ(NodeStatus::SUCCESS, state);
231 condition_R.setBoolean(
false);
233 parallel_left.setThresholdM(4);
236 std::this_thread::sleep_for(milliseconds(300));
239 ASSERT_EQ(NodeStatus::RUNNING, parallel_left.status());
240 ASSERT_EQ(NodeStatus::SUCCESS, condition_L1.status());
241 ASSERT_EQ(NodeStatus::SUCCESS, condition_L2.status());
242 ASSERT_EQ(NodeStatus::SUCCESS, action_L1.status());
243 ASSERT_EQ(NodeStatus::SUCCESS, action_L2.status());
245 ASSERT_EQ(NodeStatus::RUNNING, parallel_right.status());
248 state = parallel_root.executeTick();
250 ASSERT_EQ(NodeStatus::SUCCESS, parallel_left.status());
251 ASSERT_EQ(NodeStatus::IDLE, condition_L1.status());
252 ASSERT_EQ(NodeStatus::IDLE, condition_L2.status());
253 ASSERT_EQ(NodeStatus::IDLE, action_L1.status());
254 ASSERT_EQ(NodeStatus::IDLE, action_L2.status());
256 ASSERT_EQ(NodeStatus::RUNNING, parallel_right.status());
257 ASSERT_EQ(NodeStatus::RUNNING, action_R.status());
259 ASSERT_EQ(NodeStatus::RUNNING, state);
262 std::this_thread::sleep_for(milliseconds(300));
263 state = parallel_root.executeTick();
265 ASSERT_EQ(NodeStatus::IDLE, parallel_left.status());
266 ASSERT_EQ(NodeStatus::IDLE, action_L1.status());
268 ASSERT_EQ(NodeStatus::IDLE, parallel_right.status());
269 ASSERT_EQ(NodeStatus::IDLE, action_R.status());
271 ASSERT_EQ(NodeStatus::SUCCESS, state);
BT::AsyncActionTest action_L2
BT::ConditionTestNode condition_L2
BT::ConditionTestNode condition_2
BT::ConditionTestNode condition_R
BT::AsyncActionTest action_L1
void haltAllActions(TreeNode *root_node)
BT::ParallelNode parallel_right
void setThresholdM(unsigned int threshold_M)
BT::ParallelNode parallel_left
BT::AsyncActionTest action_R
void setTime(BT::Duration time)
BT::ConditionTestNode condition_L1
void addChild(TreeNode *child)
The method used to add nodes to the children vector.
BT::AsyncActionTest action_1
BT::ParallelNode parallel_root
NodeStatus status() const
TEST_F(SimpleParallelTest, ConditionsTrue)
virtual BT::NodeStatus executeTick()
The method that should be used to invoke tick() and setStatus();.
BT::ConditionTestNode condition_1
BT::AsyncActionTest action_2