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
00020 struct SimpleParallelTest : testing::Test
00021 {
00022 BT::ParallelNode root;
00023 BT::AsyncActionTest action_1;
00024 BT::ConditionTestNode condition_1;
00025
00026 BT::AsyncActionTest action_2;
00027 BT::ConditionTestNode condition_2;
00028
00029 SimpleParallelTest()
00030 : root("root_parallel", 4)
00031 , action_1("action_1")
00032 , condition_1("condition_1")
00033 , action_2("action_2")
00034 , condition_2("condition_2")
00035 {
00036 root.addChild(&condition_1);
00037 root.addChild(&action_1);
00038 root.addChild(&condition_2);
00039 root.addChild(&action_2);
00040 }
00041 ~SimpleParallelTest()
00042 {
00043 haltAllActions(&root);
00044 }
00045 };
00046
00047 struct ComplexParallelTest : testing::Test
00048 {
00049 BT::ParallelNode root;
00050 BT::ParallelNode parallel_1;
00051 BT::ParallelNode parallel_2;
00052
00053 BT::AsyncActionTest action_1;
00054 BT::ConditionTestNode condition_1;
00055
00056 BT::AsyncActionTest action_2;
00057 BT::ConditionTestNode condition_2;
00058
00059 BT::AsyncActionTest action_3;
00060 BT::ConditionTestNode condition_3;
00061
00062 ComplexParallelTest()
00063 : root("root", 2)
00064 , parallel_1("par1", 3)
00065 , parallel_2("par2", 1)
00066 , action_1("action_1")
00067 , condition_1("condition_1")
00068 , action_2("action_2")
00069 , condition_2("condition_2")
00070 , action_3("action_3")
00071 , condition_3("condition_3")
00072 {
00073 root.addChild(¶llel_1);
00074 {
00075 parallel_1.addChild(&condition_1);
00076 parallel_1.addChild(&action_1);
00077 parallel_1.addChild(&condition_2);
00078 parallel_1.addChild(&action_2);
00079 }
00080 root.addChild(¶llel_2);
00081 {
00082 parallel_2.addChild(&condition_3);
00083 parallel_2.addChild(&action_3);
00084 }
00085 }
00086 ~ComplexParallelTest()
00087 {
00088 haltAllActions(&root);
00089 }
00090 };
00091
00092
00093
00094 TEST_F(SimpleParallelTest, ConditionsTrue)
00095 {
00096 BT::NodeStatus state = root.executeTick();
00097
00098 ASSERT_EQ(NodeStatus::IDLE, condition_1.status());
00099 ASSERT_EQ(NodeStatus::IDLE, condition_2.status());
00100 ASSERT_EQ(NodeStatus::RUNNING, action_1.status());
00101 ASSERT_EQ(NodeStatus::RUNNING, action_2.status());
00102 ASSERT_EQ(NodeStatus::RUNNING, state);
00103 }
00104
00105 TEST_F(SimpleParallelTest, Threshold_3)
00106 {
00107 root.setThresholdM(3);
00108 action_2.setTime(200);
00109 root.executeTick();
00110 std::this_thread::sleep_for(std::chrono::milliseconds(500));
00111 BT::NodeStatus state = root.executeTick();
00112
00113 ASSERT_EQ(NodeStatus::IDLE, condition_1.status());
00114 ASSERT_EQ(NodeStatus::IDLE, condition_2.status());
00115 ASSERT_EQ(NodeStatus::IDLE, action_1.status());
00116 ASSERT_EQ(NodeStatus::IDLE, action_2.status());
00117 ASSERT_EQ(NodeStatus::SUCCESS, state);
00118 }
00119
00120 TEST_F(SimpleParallelTest, Threshold_1)
00121 {
00122 root.setThresholdM(1);
00123 BT::NodeStatus state = root.executeTick();
00124
00125 ASSERT_EQ(NodeStatus::IDLE, condition_1.status());
00126 ASSERT_EQ(NodeStatus::IDLE, condition_2.status());
00127 ASSERT_EQ(NodeStatus::IDLE, action_1.status());
00128 ASSERT_EQ(NodeStatus::IDLE, action_2.status());
00129 ASSERT_EQ(NodeStatus::SUCCESS, state);
00130 }
00131 TEST_F(ComplexParallelTest, ConditionsTrue)
00132 {
00133 BT::NodeStatus state = root.executeTick();
00134
00135 ASSERT_EQ(NodeStatus::IDLE, condition_1.status());
00136 ASSERT_EQ(NodeStatus::IDLE, condition_2.status());
00137 ASSERT_EQ(NodeStatus::IDLE, condition_3.status());
00138 ASSERT_EQ(NodeStatus::RUNNING, action_1.status());
00139 ASSERT_EQ(NodeStatus::RUNNING, action_2.status());
00140 ASSERT_EQ(NodeStatus::IDLE, action_3.status());
00141 ASSERT_EQ(NodeStatus::RUNNING, parallel_1.status());
00142 ASSERT_EQ(NodeStatus::IDLE, parallel_2.status());
00143 ASSERT_EQ(NodeStatus::RUNNING, state);
00144 }
00145
00146 TEST_F(ComplexParallelTest, Condition3False)
00147 {
00148 condition_3.setBoolean(false);
00149 BT::NodeStatus state = root.executeTick();
00150
00151 ASSERT_EQ(NodeStatus::IDLE, condition_1.status());
00152 ASSERT_EQ(NodeStatus::IDLE, condition_2.status());
00153 ASSERT_EQ(NodeStatus::IDLE, condition_3.status());
00154 ASSERT_EQ(NodeStatus::RUNNING, action_1.status());
00155 ASSERT_EQ(NodeStatus::RUNNING, action_2.status());
00156 ASSERT_EQ(NodeStatus::RUNNING, action_3.status());
00157 ASSERT_EQ(NodeStatus::RUNNING, parallel_1.status());
00158 ASSERT_EQ(NodeStatus::RUNNING, parallel_2.status());
00159 ASSERT_EQ(NodeStatus::RUNNING, state);
00160 }
00161
00162 TEST_F(ComplexParallelTest, Condition3FalseAction1Done)
00163 {
00164 action_2.setTime(10);
00165 action_3.setTime(10);
00166
00167 condition_3.setBoolean(false);
00168 BT::NodeStatus state = root.executeTick();
00169 std::this_thread::sleep_for(std::chrono::milliseconds(500));
00170
00171 ASSERT_EQ(NodeStatus::IDLE, condition_1.status());
00172 ASSERT_EQ(NodeStatus::IDLE, condition_2.status());
00173 ASSERT_EQ(NodeStatus::IDLE, condition_3.status());
00174 ASSERT_EQ(NodeStatus::SUCCESS,
00175 action_1.status());
00176 ASSERT_EQ(NodeStatus::RUNNING,
00177 parallel_1.status());
00178
00179 state = root.executeTick();
00180
00181 ASSERT_EQ(NodeStatus::IDLE, action_1.status());
00182 ASSERT_EQ(NodeStatus::IDLE, parallel_1.status());
00183 ASSERT_EQ(NodeStatus::IDLE, action_2.status());
00184 ASSERT_EQ(NodeStatus::RUNNING, action_3.status());
00185 ASSERT_EQ(NodeStatus::RUNNING, parallel_2.status());
00186 ASSERT_EQ(NodeStatus::RUNNING, state);
00187
00188 state = root.executeTick();
00189 std::this_thread::sleep_for(std::chrono::milliseconds(1500));
00190 state = root.executeTick();
00191
00192 ASSERT_EQ(NodeStatus::IDLE, parallel_2.status());
00193 ASSERT_EQ(NodeStatus::IDLE, action_1.status());
00194 ASSERT_EQ(NodeStatus::IDLE, parallel_1.status());
00195 ASSERT_EQ(NodeStatus::IDLE, action_3.status());
00196 ASSERT_EQ(NodeStatus::IDLE, parallel_2.status());
00197 ASSERT_EQ(NodeStatus::SUCCESS, state);
00198 }