Go to the documentation of this file.00001
00002
00003
00004
00005
00006
00007
00008
00009
00010
00011
00012
00013 #include <gtest/gtest.h>
00014 #include "action_test_node.h"
00015 #include "condition_test_node.h"
00016 #include "behaviortree_cpp/behavior_tree.h"
00017
00018 using BT::NodeStatus;
00019 using std::chrono::milliseconds;
00020
00021 struct BehaviorTreeTest : testing::Test
00022 {
00023 BT::SequenceNode root;
00024 BT::AsyncActionTest action_1;
00025 BT::ConditionTestNode condition_1;
00026 BT::ConditionTestNode condition_2;
00027
00028 BT::FallbackNode fal_conditions;
00029
00030 BehaviorTreeTest()
00031 : root("root_sequence")
00032 , action_1("action_1", milliseconds(100) )
00033 , condition_1("condition_1")
00034 , condition_2("condition_2")
00035 , fal_conditions("fallback_conditions")
00036 {
00037 root.addChild(&fal_conditions);
00038 {
00039 fal_conditions.addChild(&condition_1);
00040 fal_conditions.addChild(&condition_2);
00041 }
00042 root.addChild(&action_1);
00043 }
00044 ~BehaviorTreeTest()
00045 {
00046 haltAllActions(&root);
00047 }
00048 };
00049
00050
00051
00052 TEST_F(BehaviorTreeTest, Condition1ToFalseCondition2True)
00053 {
00054 condition_1.setBoolean(false);
00055 condition_2.setBoolean(true);
00056
00057 BT::NodeStatus state = root.executeTick();
00058
00059 ASSERT_EQ(NodeStatus::RUNNING, state);
00060 ASSERT_EQ(NodeStatus::SUCCESS, fal_conditions.status());
00061 ASSERT_EQ(NodeStatus::IDLE, condition_1.status());
00062 ASSERT_EQ(NodeStatus::IDLE, condition_2.status());
00063 ASSERT_EQ(NodeStatus::RUNNING, action_1.status());
00064 }
00065
00066 TEST_F(BehaviorTreeTest, Condition2ToFalseCondition1True)
00067 {
00068 condition_2.setBoolean(false);
00069 condition_1.setBoolean(true);
00070
00071 BT::NodeStatus state = root.executeTick();
00072
00073 ASSERT_EQ(NodeStatus::RUNNING, state);
00074 ASSERT_EQ(NodeStatus::SUCCESS, fal_conditions.status());
00075 ASSERT_EQ(NodeStatus::IDLE, condition_1.status());
00076 ASSERT_EQ(NodeStatus::IDLE, condition_2.status());
00077 ASSERT_EQ(NodeStatus::RUNNING, action_1.status());
00078 }
00079
00080 int main(int argc, char** argv)
00081 {
00082 testing::InitGoogleTest(&argc, argv);
00083 return RUN_ALL_TESTS();
00084 }