13 #include <gtest/gtest.h> 20 using std::chrono::milliseconds;
29 root(
"root_fallback"), condition(
"condition"), action(
"action", milliseconds(100))
47 condition_1(
"condition_1"),
48 condition_2(
"condition_2"),
49 action_1(
"action_1", milliseconds(100))
66 root(
"root_sequence"), action(
"action", milliseconds(100)), condition(
"condition")
89 root(
"root_fallback"),
90 action_1(
"action_1", milliseconds(100)),
91 action_2(
"action_2", milliseconds(100)),
92 condition_1(
"condition_1"),
93 condition_2(
"condition_2"),
94 fal_conditions(
"fallback_conditions"),
95 fal_actions(
"fallback_actions")
99 fal_conditions.
addChild(&condition_1);
100 fal_conditions.
addChild(&condition_2);
120 ASSERT_EQ(NodeStatus::SUCCESS, state);
132 ASSERT_EQ(NodeStatus::RUNNING, state);
139 ASSERT_EQ(NodeStatus::RUNNING, state);
146 condition_1.setExpectedResult(NodeStatus::FAILURE);
147 condition_2.setExpectedResult(NodeStatus::FAILURE);
151 ASSERT_EQ(NodeStatus::RUNNING, state);
152 ASSERT_EQ(NodeStatus::FAILURE, condition_1.status());
153 ASSERT_EQ(NodeStatus::FAILURE, condition_2.status());
154 ASSERT_EQ(NodeStatus::RUNNING, action_1.status());
156 condition_1.setExpectedResult(NodeStatus::SUCCESS);
160 ASSERT_EQ(NodeStatus::SUCCESS, state);
161 ASSERT_EQ(NodeStatus::IDLE, condition_1.status());
162 ASSERT_EQ(NodeStatus::IDLE, condition_2.status());
163 ASSERT_EQ(NodeStatus::IDLE, action_1.status());
168 condition_1.setExpectedResult(NodeStatus::FAILURE);
169 condition_2.setExpectedResult(NodeStatus::FAILURE);
173 ASSERT_EQ(NodeStatus::RUNNING, state);
174 ASSERT_EQ(NodeStatus::FAILURE, condition_1.status());
175 ASSERT_EQ(NodeStatus::FAILURE, condition_2.status());
176 ASSERT_EQ(NodeStatus::RUNNING, action_1.status());
178 condition_2.setExpectedResult(NodeStatus::SUCCESS);
182 ASSERT_EQ(NodeStatus::SUCCESS, state);
183 ASSERT_EQ(NodeStatus::IDLE, condition_1.status());
184 ASSERT_EQ(NodeStatus::IDLE, condition_2.status());
185 ASSERT_EQ(NodeStatus::IDLE, action_1.status());
193 ASSERT_EQ(NodeStatus::RUNNING, state);
203 ASSERT_EQ(NodeStatus::RUNNING, state);
210 ASSERT_EQ(NodeStatus::RUNNING, state);
219 ASSERT_EQ(NodeStatus::SUCCESS, state);
220 ASSERT_EQ(NodeStatus::IDLE, fal_conditions.status());
221 ASSERT_EQ(NodeStatus::IDLE, condition_1.status());
222 ASSERT_EQ(NodeStatus::IDLE, condition_2.status());
223 ASSERT_EQ(NodeStatus::IDLE, fal_actions.status());
224 ASSERT_EQ(NodeStatus::IDLE, action_1.status());
225 ASSERT_EQ(NodeStatus::IDLE, action_2.status());
230 condition_1.setExpectedResult(NodeStatus::FAILURE);
233 ASSERT_EQ(NodeStatus::SUCCESS, state);
234 ASSERT_EQ(NodeStatus::IDLE, fal_conditions.status());
235 ASSERT_EQ(NodeStatus::IDLE, condition_1.status());
236 ASSERT_EQ(NodeStatus::IDLE, condition_2.status());
237 ASSERT_EQ(NodeStatus::IDLE, fal_actions.status());
238 ASSERT_EQ(NodeStatus::IDLE, action_1.status());
239 ASSERT_EQ(NodeStatus::IDLE, action_2.status());
244 condition_1.setExpectedResult(NodeStatus::FAILURE);
245 condition_2.setExpectedResult(NodeStatus::FAILURE);
248 ASSERT_EQ(NodeStatus::RUNNING, state);
249 ASSERT_EQ(NodeStatus::FAILURE, fal_conditions.status());
250 ASSERT_EQ(NodeStatus::IDLE, condition_1.status());
251 ASSERT_EQ(NodeStatus::IDLE, condition_2.status());
252 ASSERT_EQ(NodeStatus::RUNNING, fal_actions.status());
253 ASSERT_EQ(NodeStatus::RUNNING, action_1.status());
254 ASSERT_EQ(NodeStatus::IDLE, action_2.status());
259 condition_1.setExpectedResult(NodeStatus::FAILURE);
260 condition_2.setExpectedResult(NodeStatus::FAILURE);
263 condition_1.setExpectedResult(NodeStatus::SUCCESS);
266 ASSERT_EQ(NodeStatus::RUNNING, state);
267 ASSERT_EQ(NodeStatus::FAILURE, fal_conditions.status());
268 ASSERT_EQ(NodeStatus::IDLE, condition_1.status());
269 ASSERT_EQ(NodeStatus::IDLE, condition_2.status());
270 ASSERT_EQ(NodeStatus::RUNNING, fal_actions.status());
271 ASSERT_EQ(NodeStatus::RUNNING, action_1.status());
272 ASSERT_EQ(NodeStatus::IDLE, action_2.status());
277 condition_1.setExpectedResult(NodeStatus::FAILURE);
278 condition_2.setExpectedResult(NodeStatus::FAILURE);
281 condition_2.setExpectedResult(NodeStatus::SUCCESS);
284 ASSERT_EQ(NodeStatus::RUNNING, state);
285 ASSERT_EQ(NodeStatus::FAILURE, fal_conditions.status());
286 ASSERT_EQ(NodeStatus::IDLE, condition_1.status());
287 ASSERT_EQ(NodeStatus::IDLE, condition_2.status());
288 ASSERT_EQ(NodeStatus::RUNNING, fal_actions.status());
289 ASSERT_EQ(NodeStatus::RUNNING, action_1.status());
290 ASSERT_EQ(NodeStatus::IDLE, action_2.status());
295 action_1.setExpectedResult(NodeStatus::FAILURE);
296 action_2.setExpectedResult(NodeStatus::SUCCESS);
297 condition_1.setExpectedResult(NodeStatus::FAILURE);
298 condition_2.setExpectedResult(NodeStatus::FAILURE);
303 std::this_thread::sleep_for(std::chrono::milliseconds(500));
306 ASSERT_EQ(NodeStatus::RUNNING, state);
307 ASSERT_EQ(NodeStatus::FAILURE, fal_conditions.status());
308 ASSERT_EQ(NodeStatus::IDLE, condition_1.status());
309 ASSERT_EQ(NodeStatus::IDLE, condition_2.status());
310 ASSERT_EQ(NodeStatus::RUNNING, fal_actions.status());
311 ASSERT_EQ(NodeStatus::FAILURE, action_1.status());
312 ASSERT_EQ(NodeStatus::RUNNING, action_2.status());
316 TEST(FallbackAndRetry, FallbackAndRetry)
321 <root main_tree_to_execute="BehaviorTree"> 322 <BehaviorTree ID="BehaviorTree"> 323 <RetryUntilSuccessful num_attempts="2"> 325 <AsyncActionTest name="first"/> 327 <AsyncActionTest name="second"/> 330 </RetryUntilSuccessful> 340 std::vector<AsyncActionTest*> async;
342 for(
auto node: tree.nodes) {
343 if(
auto async_node = dynamic_cast<AsyncActionTest*>(node.get()) )
345 async.push_back(async_node);
349 ASSERT_EQ(async.size(), 2);
350 async[0]->setExpectedResult(NodeStatus::FAILURE);
351 async[1]->setExpectedResult(NodeStatus::SUCCESS);
353 auto res = tree.tickRootWhileRunning();
355 ASSERT_EQ(async[0]->failureCount(), 2);
356 ASSERT_EQ(async[0]->successCount(), 0);
358 ASSERT_EQ(async[1]->failureCount(), 0);
359 ASSERT_EQ(async[1]->successCount(), 2);
361 ASSERT_EQ(NodeStatus::FAILURE, res);
BT::AsyncActionTest action_1
BT::AsyncActionTest action
void registerNodeType(const std::string &ID)
BT::ConditionTestNode condition
BT::ConditionTestNode condition
NodeStatus status() const
BT::AsyncActionTest action_2
~ComplexFallbackWithMemoryTest()
BT::ReactiveFallback root
static const char * xml_text
BT::ConditionTestNode condition_1
BT::ConditionTestNode condition_2
void setExpectedResult(NodeStatus res)
The BehaviorTreeFactory is used to create instances of a TreeNode at run-time.
BT::FallbackNode fal_conditions
TEST(FallbackAndRetry, FallbackAndRetry)
BT::AsyncActionTest action_1
Tree createTreeFromText(const std::string &text, Blackboard::Ptr blackboard=Blackboard::create())
BT::FallbackNode fal_actions
void addChild(TreeNode *child)
The method used to add nodes to the children vector.
The ReactiveFallback is similar to a ParallelNode. All the children are ticked from first to last: ...
BT::AsyncActionTest action
ComplexFallbackWithMemoryTest()
~SimpleFallbackWithMemoryTest()
BT::ConditionTestNode condition_2
virtual BT::NodeStatus executeTick()
The method that should be used to invoke tick() and setStatus();.
The FallbackNode is used to try different strategies, until one succeeds. If any child returns RUNNIN...
SimpleFallbackWithMemoryTest()
BT::ConditionTestNode condition_1
TEST_F(SimpleFallbackTest, ConditionTrue)