13 #include <gtest/gtest.h> 47 : root(
"root_fallback")
48 , action_1(
"action_1")
49 , condition_1(
"condition_1")
50 , condition_2(
"condition_2")
51 , fal_conditions(
"fallback_conditions")
55 fal_conditions.
addChild(&condition_1);
56 fal_conditions.
addChild(&condition_2);
97 : root(
"root_fallback")
98 , action_1(
"action_1")
99 , action_2(
"action_2")
100 , condition_1(
"condition_1")
101 , condition_2(
"condition_2")
102 , fal_conditions(
"fallback_conditions")
103 , fal_actions(
"fallback_actions")
107 fal_conditions.
addChild(&condition_1);
108 fal_conditions.
addChild(&condition_2);
126 std::cout <<
"Ticking the root node !" << std::endl << std::endl;
131 ASSERT_EQ(NodeStatus::SUCCESS, state);
145 ASSERT_EQ(NodeStatus::SUCCESS, state);
152 condition_1.setBoolean(
false);
153 condition_2.setBoolean(
false);
157 ASSERT_EQ(NodeStatus::RUNNING, state);
158 ASSERT_EQ(NodeStatus::FAILURE, fal_conditions.status());
159 ASSERT_EQ(NodeStatus::IDLE, condition_1.status());
160 ASSERT_EQ(NodeStatus::IDLE, condition_2.status());
161 ASSERT_EQ(NodeStatus::RUNNING, action_1.status());
163 condition_1.setBoolean(
true);
167 ASSERT_EQ(NodeStatus::SUCCESS, state);
168 ASSERT_EQ(NodeStatus::IDLE, fal_conditions.status());
169 ASSERT_EQ(NodeStatus::IDLE, condition_1.status());
170 ASSERT_EQ(NodeStatus::IDLE, condition_2.status());
171 ASSERT_EQ(NodeStatus::IDLE, action_1.status());
176 condition_1.setBoolean(
false);
177 condition_2.setBoolean(
false);
181 ASSERT_EQ(NodeStatus::RUNNING, state);
182 ASSERT_EQ(NodeStatus::FAILURE, fal_conditions.status());
183 ASSERT_EQ(NodeStatus::IDLE, condition_1.status());
184 ASSERT_EQ(NodeStatus::IDLE, condition_2.status());
185 ASSERT_EQ(NodeStatus::RUNNING, action_1.status());
187 condition_2.setBoolean(
true);
191 ASSERT_EQ(NodeStatus::SUCCESS, state);
192 ASSERT_EQ(NodeStatus::IDLE, fal_conditions.status());
193 ASSERT_EQ(NodeStatus::IDLE, condition_1.status());
194 ASSERT_EQ(NodeStatus::IDLE, condition_2.status());
195 ASSERT_EQ(NodeStatus::IDLE, action_1.status());
202 std::this_thread::sleep_for(std::chrono::milliseconds(100));
204 ASSERT_EQ(NodeStatus::RUNNING, state);
214 ASSERT_EQ(NodeStatus::RUNNING, state);
221 ASSERT_EQ(NodeStatus::RUNNING, state);
230 ASSERT_EQ(NodeStatus::SUCCESS, state);
231 ASSERT_EQ(NodeStatus::IDLE, fal_conditions.status());
232 ASSERT_EQ(NodeStatus::IDLE, condition_1.status());
233 ASSERT_EQ(NodeStatus::IDLE, condition_2.status());
234 ASSERT_EQ(NodeStatus::IDLE, fal_actions.status());
235 ASSERT_EQ(NodeStatus::IDLE, action_1.status());
236 ASSERT_EQ(NodeStatus::IDLE, action_2.status());
241 condition_1.setBoolean(
false);
244 ASSERT_EQ(NodeStatus::SUCCESS, state);
245 ASSERT_EQ(NodeStatus::IDLE, fal_conditions.status());
246 ASSERT_EQ(NodeStatus::IDLE, condition_1.status());
247 ASSERT_EQ(NodeStatus::IDLE, condition_2.status());
248 ASSERT_EQ(NodeStatus::IDLE, fal_actions.status());
249 ASSERT_EQ(NodeStatus::IDLE, action_1.status());
250 ASSERT_EQ(NodeStatus::IDLE, action_2.status());
255 condition_1.setBoolean(
false);
256 condition_2.setBoolean(
false);
259 ASSERT_EQ(NodeStatus::RUNNING, state);
260 ASSERT_EQ(NodeStatus::FAILURE, fal_conditions.status());
261 ASSERT_EQ(NodeStatus::IDLE, condition_1.status());
262 ASSERT_EQ(NodeStatus::IDLE, condition_2.status());
263 ASSERT_EQ(NodeStatus::RUNNING, fal_actions.status());
264 ASSERT_EQ(NodeStatus::RUNNING, action_1.status());
265 ASSERT_EQ(NodeStatus::IDLE, action_2.status());
270 condition_1.setBoolean(
false);
271 condition_2.setBoolean(
false);
274 condition_1.setBoolean(
true);
277 ASSERT_EQ(NodeStatus::RUNNING, state);
278 ASSERT_EQ(NodeStatus::FAILURE, fal_conditions.status());
279 ASSERT_EQ(NodeStatus::IDLE, condition_1.status());
280 ASSERT_EQ(NodeStatus::IDLE, condition_2.status());
281 ASSERT_EQ(NodeStatus::RUNNING, fal_actions.status());
282 ASSERT_EQ(NodeStatus::RUNNING, action_1.status());
283 ASSERT_EQ(NodeStatus::IDLE, action_2.status());
288 condition_1.setBoolean(
false);
289 condition_2.setBoolean(
false);
292 condition_2.setBoolean(
true);
295 ASSERT_EQ(NodeStatus::RUNNING, state);
296 ASSERT_EQ(NodeStatus::FAILURE, fal_conditions.status());
297 ASSERT_EQ(NodeStatus::IDLE, condition_1.status());
298 ASSERT_EQ(NodeStatus::IDLE, condition_2.status());
299 ASSERT_EQ(NodeStatus::RUNNING, fal_actions.status());
300 ASSERT_EQ(NodeStatus::RUNNING, action_1.status());
301 ASSERT_EQ(NodeStatus::IDLE, action_2.status());
306 action_1.setBoolean(
false);
307 condition_1.setBoolean(
false);
308 condition_2.setBoolean(
false);
313 std::this_thread::sleep_for(std::chrono::milliseconds(500));
316 ASSERT_EQ(NodeStatus::RUNNING, state);
317 ASSERT_EQ(NodeStatus::FAILURE, fal_conditions.status());
318 ASSERT_EQ(NodeStatus::IDLE, condition_1.status());
319 ASSERT_EQ(NodeStatus::IDLE, condition_2.status());
320 ASSERT_EQ(NodeStatus::RUNNING, fal_actions.status());
321 ASSERT_EQ(NodeStatus::FAILURE, action_1.status());
322 ASSERT_EQ(NodeStatus::RUNNING, action_2.status());
BT::FallbackStarNode fal_conditions
BT::AsyncActionTest action_1
BT::AsyncActionTest action
BT::ConditionTestNode condition
BT::ConditionTestNode condition
BT::FallbackStarNode root
void setBoolean(bool boolean_value)
BT::AsyncActionTest action_2
~ComplexFallbackWithMemoryTest()
BT::ConditionTestNode condition_2
BT::AsyncActionTest action_1
BT::FallbackNode fal_conditions
void haltAllActions(TreeNode *root_node)
The FallbackStarNode is used to try different strategies, until one succeed. If any child returns RUN...
BT::ConditionTestNode condition_1
BT::FallbackStarNode root
void addChild(TreeNode *child)
BT::FallbackStarNode fal_actions
NodeStatus status() const
BT::AsyncActionTest action
ComplexFallbackWithMemoryTest()
~SimpleFallbackWithMemoryTest()
BT::ConditionTestNode condition_2
virtual BT::NodeStatus executeTick()
The method that will be executed to invoke tick(); and setStatus();.
The FallbackNode is used to try different strategies, until one succeed. If any child returns RUNNING...
SimpleFallbackWithMemoryTest()
BT::ConditionTestNode condition_1
TEST_F(SimpleFallbackTest, ConditionTrue)