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 SimpleFallbackTest : testing::Test
00021 {
00022 BT::FallbackNode root;
00023 BT::AsyncActionTest action;
00024 BT::ConditionTestNode condition;
00025
00026 SimpleFallbackTest() : root("root_fallback"), action("action"), condition("condition")
00027 {
00028 root.addChild(&condition);
00029 root.addChild(&action);
00030 }
00031 ~SimpleFallbackTest()
00032 {
00033 haltAllActions(&root);
00034 }
00035 };
00036
00037 struct ComplexFallbackTest : testing::Test
00038 {
00039 BT::FallbackNode root;
00040 BT::AsyncActionTest action_1;
00041 BT::ConditionTestNode condition_1;
00042 BT::ConditionTestNode condition_2;
00043
00044 BT::FallbackNode fal_conditions;
00045
00046 ComplexFallbackTest()
00047 : root("root_fallback")
00048 , action_1("action_1")
00049 , condition_1("condition_1")
00050 , condition_2("condition_2")
00051 , fal_conditions("fallback_conditions")
00052 {
00053 root.addChild(&fal_conditions);
00054 {
00055 fal_conditions.addChild(&condition_1);
00056 fal_conditions.addChild(&condition_2);
00057 }
00058 root.addChild(&action_1);
00059 }
00060 ~ComplexFallbackTest()
00061 {
00062 haltAllActions(&root);
00063 }
00064 };
00065
00066 struct SimpleFallbackWithMemoryTest : testing::Test
00067 {
00068 BT::FallbackStarNode root;
00069 BT::AsyncActionTest action;
00070 BT::ConditionTestNode condition;
00071
00072 SimpleFallbackWithMemoryTest() : root("root_sequence"), action("action"), condition("condition")
00073 {
00074 root.addChild(&condition);
00075 root.addChild(&action);
00076 }
00077 ~SimpleFallbackWithMemoryTest()
00078 {
00079 haltAllActions(&root);
00080 }
00081 };
00082
00083 struct ComplexFallbackWithMemoryTest : testing::Test
00084 {
00085 BT::FallbackStarNode root;
00086
00087 BT::AsyncActionTest action_1;
00088 BT::AsyncActionTest action_2;
00089
00090 BT::ConditionTestNode condition_1;
00091 BT::ConditionTestNode condition_2;
00092
00093 BT::FallbackStarNode fal_conditions;
00094 BT::FallbackStarNode fal_actions;
00095
00096 ComplexFallbackWithMemoryTest()
00097 : root("root_fallback")
00098 , action_1("action_1")
00099 , action_2("action_2")
00100 , condition_1("condition_1")
00101 , condition_2("condition_2")
00102 , fal_conditions("fallback_conditions")
00103 , fal_actions("fallback_actions")
00104 {
00105 root.addChild(&fal_conditions);
00106 {
00107 fal_conditions.addChild(&condition_1);
00108 fal_conditions.addChild(&condition_2);
00109 }
00110 root.addChild(&fal_actions);
00111 {
00112 fal_actions.addChild(&action_1);
00113 fal_actions.addChild(&action_2);
00114 }
00115 }
00116 ~ComplexFallbackWithMemoryTest()
00117 {
00118 haltAllActions(&root);
00119 }
00120 };
00121
00122
00123
00124 TEST_F(SimpleFallbackTest, ConditionTrue)
00125 {
00126 std::cout << "Ticking the root node !" << std::endl << std::endl;
00127
00128 condition.setBoolean(true);
00129 BT::NodeStatus state = root.executeTick();
00130
00131 ASSERT_EQ(NodeStatus::SUCCESS, state);
00132 ASSERT_EQ(NodeStatus::IDLE, condition.status());
00133 ASSERT_EQ(NodeStatus::IDLE, action.status());
00134 }
00135
00136 TEST_F(SimpleFallbackTest, ConditionToFalse)
00137 {
00138 condition.setBoolean(false);
00139
00140 BT::NodeStatus state = root.executeTick();
00141 condition.setBoolean(true);
00142
00143 state = root.executeTick();
00144
00145 ASSERT_EQ(NodeStatus::SUCCESS, state);
00146 ASSERT_EQ(NodeStatus::IDLE, condition.status());
00147 ASSERT_EQ(NodeStatus::IDLE, action.status());
00148 }
00149
00150 TEST_F(ComplexFallbackTest, Condition1ToTrue)
00151 {
00152 condition_1.setBoolean(false);
00153 condition_2.setBoolean(false);
00154
00155 BT::NodeStatus state = root.executeTick();
00156
00157 ASSERT_EQ(NodeStatus::RUNNING, state);
00158 ASSERT_EQ(NodeStatus::FAILURE, fal_conditions.status());
00159 ASSERT_EQ(NodeStatus::IDLE, condition_1.status());
00160 ASSERT_EQ(NodeStatus::IDLE, condition_2.status());
00161 ASSERT_EQ(NodeStatus::RUNNING, action_1.status());
00162
00163 condition_1.setBoolean(true);
00164
00165 state = root.executeTick();
00166
00167 ASSERT_EQ(NodeStatus::SUCCESS, state);
00168 ASSERT_EQ(NodeStatus::IDLE, fal_conditions.status());
00169 ASSERT_EQ(NodeStatus::IDLE, condition_1.status());
00170 ASSERT_EQ(NodeStatus::IDLE, condition_2.status());
00171 ASSERT_EQ(NodeStatus::IDLE, action_1.status());
00172 }
00173
00174 TEST_F(ComplexFallbackTest, Condition2ToTrue)
00175 {
00176 condition_1.setBoolean(false);
00177 condition_2.setBoolean(false);
00178
00179 BT::NodeStatus state = root.executeTick();
00180
00181 ASSERT_EQ(NodeStatus::RUNNING, state);
00182 ASSERT_EQ(NodeStatus::FAILURE, fal_conditions.status());
00183 ASSERT_EQ(NodeStatus::IDLE, condition_1.status());
00184 ASSERT_EQ(NodeStatus::IDLE, condition_2.status());
00185 ASSERT_EQ(NodeStatus::RUNNING, action_1.status());
00186
00187 condition_2.setBoolean(true);
00188
00189 state = root.executeTick();
00190
00191 ASSERT_EQ(NodeStatus::SUCCESS, state);
00192 ASSERT_EQ(NodeStatus::IDLE, fal_conditions.status());
00193 ASSERT_EQ(NodeStatus::IDLE, condition_1.status());
00194 ASSERT_EQ(NodeStatus::IDLE, condition_2.status());
00195 ASSERT_EQ(NodeStatus::IDLE, action_1.status());
00196 }
00197
00198 TEST_F(SimpleFallbackWithMemoryTest, ConditionFalse)
00199 {
00200 condition.setBoolean(false);
00201 BT::NodeStatus state = root.executeTick();
00202 std::this_thread::sleep_for(std::chrono::milliseconds(100));
00203
00204 ASSERT_EQ(NodeStatus::RUNNING, state);
00205 ASSERT_EQ(NodeStatus::FAILURE, condition.status());
00206 ASSERT_EQ(NodeStatus::RUNNING, action.status());
00207 }
00208
00209 TEST_F(SimpleFallbackWithMemoryTest, ConditionTurnToTrue)
00210 {
00211 condition.setBoolean(false);
00212 BT::NodeStatus state = root.executeTick();
00213
00214 ASSERT_EQ(NodeStatus::RUNNING, state);
00215 ASSERT_EQ(NodeStatus::FAILURE, condition.status());
00216 ASSERT_EQ(NodeStatus::RUNNING, action.status());
00217
00218 condition.setBoolean(true);
00219 state = root.executeTick();
00220
00221 ASSERT_EQ(NodeStatus::RUNNING, state);
00222 ASSERT_EQ(NodeStatus::FAILURE, condition.status());
00223 ASSERT_EQ(NodeStatus::RUNNING, action.status());
00224 }
00225
00226 TEST_F(ComplexFallbackWithMemoryTest, ConditionsTrue)
00227 {
00228 BT::NodeStatus state = root.executeTick();
00229
00230 ASSERT_EQ(NodeStatus::SUCCESS, state);
00231 ASSERT_EQ(NodeStatus::IDLE, fal_conditions.status());
00232 ASSERT_EQ(NodeStatus::IDLE, condition_1.status());
00233 ASSERT_EQ(NodeStatus::IDLE, condition_2.status());
00234 ASSERT_EQ(NodeStatus::IDLE, fal_actions.status());
00235 ASSERT_EQ(NodeStatus::IDLE, action_1.status());
00236 ASSERT_EQ(NodeStatus::IDLE, action_2.status());
00237 }
00238
00239 TEST_F(ComplexFallbackWithMemoryTest, Condition1False)
00240 {
00241 condition_1.setBoolean(false);
00242 BT::NodeStatus state = root.executeTick();
00243
00244 ASSERT_EQ(NodeStatus::SUCCESS, state);
00245 ASSERT_EQ(NodeStatus::IDLE, fal_conditions.status());
00246 ASSERT_EQ(NodeStatus::IDLE, condition_1.status());
00247 ASSERT_EQ(NodeStatus::IDLE, condition_2.status());
00248 ASSERT_EQ(NodeStatus::IDLE, fal_actions.status());
00249 ASSERT_EQ(NodeStatus::IDLE, action_1.status());
00250 ASSERT_EQ(NodeStatus::IDLE, action_2.status());
00251 }
00252
00253 TEST_F(ComplexFallbackWithMemoryTest, ConditionsFalse)
00254 {
00255 condition_1.setBoolean(false);
00256 condition_2.setBoolean(false);
00257 BT::NodeStatus state = root.executeTick();
00258
00259 ASSERT_EQ(NodeStatus::RUNNING, state);
00260 ASSERT_EQ(NodeStatus::FAILURE, fal_conditions.status());
00261 ASSERT_EQ(NodeStatus::IDLE, condition_1.status());
00262 ASSERT_EQ(NodeStatus::IDLE, condition_2.status());
00263 ASSERT_EQ(NodeStatus::RUNNING, fal_actions.status());
00264 ASSERT_EQ(NodeStatus::RUNNING, action_1.status());
00265 ASSERT_EQ(NodeStatus::IDLE, action_2.status());
00266 }
00267
00268 TEST_F(ComplexFallbackWithMemoryTest, Conditions1ToTrue)
00269 {
00270 condition_1.setBoolean(false);
00271 condition_2.setBoolean(false);
00272 BT::NodeStatus state = root.executeTick();
00273
00274 condition_1.setBoolean(true);
00275 state = root.executeTick();
00276
00277 ASSERT_EQ(NodeStatus::RUNNING, state);
00278 ASSERT_EQ(NodeStatus::FAILURE, fal_conditions.status());
00279 ASSERT_EQ(NodeStatus::IDLE, condition_1.status());
00280 ASSERT_EQ(NodeStatus::IDLE, condition_2.status());
00281 ASSERT_EQ(NodeStatus::RUNNING, fal_actions.status());
00282 ASSERT_EQ(NodeStatus::RUNNING, action_1.status());
00283 ASSERT_EQ(NodeStatus::IDLE, action_2.status());
00284 }
00285
00286 TEST_F(ComplexFallbackWithMemoryTest, Conditions2ToTrue)
00287 {
00288 condition_1.setBoolean(false);
00289 condition_2.setBoolean(false);
00290 BT::NodeStatus state = root.executeTick();
00291
00292 condition_2.setBoolean(true);
00293 state = root.executeTick();
00294
00295 ASSERT_EQ(NodeStatus::RUNNING, state);
00296 ASSERT_EQ(NodeStatus::FAILURE, fal_conditions.status());
00297 ASSERT_EQ(NodeStatus::IDLE, condition_1.status());
00298 ASSERT_EQ(NodeStatus::IDLE, condition_2.status());
00299 ASSERT_EQ(NodeStatus::RUNNING, fal_actions.status());
00300 ASSERT_EQ(NodeStatus::RUNNING, action_1.status());
00301 ASSERT_EQ(NodeStatus::IDLE, action_2.status());
00302 }
00303
00304 TEST_F(ComplexFallbackWithMemoryTest, Action1Failed)
00305 {
00306 action_1.setBoolean(false);
00307 condition_1.setBoolean(false);
00308 condition_2.setBoolean(false);
00309
00310 BT::NodeStatus state = root.executeTick();
00311
00312 state = root.executeTick();
00313 std::this_thread::sleep_for(std::chrono::milliseconds(500));
00314 state = root.executeTick();
00315
00316 ASSERT_EQ(NodeStatus::RUNNING, state);
00317 ASSERT_EQ(NodeStatus::FAILURE, fal_conditions.status());
00318 ASSERT_EQ(NodeStatus::IDLE, condition_1.status());
00319 ASSERT_EQ(NodeStatus::IDLE, condition_2.status());
00320 ASSERT_EQ(NodeStatus::RUNNING, fal_actions.status());
00321 ASSERT_EQ(NodeStatus::FAILURE, action_1.status());
00322 ASSERT_EQ(NodeStatus::RUNNING, action_2.status());
00323 }