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 SimpleFallbackTest : testing::Test
00022 {
00023 BT::FallbackNode root;
00024 BT::ConditionTestNode condition;
00025 BT::AsyncActionTest action;
00026
00027 SimpleFallbackTest() :
00028 root("root_fallback")
00029 , condition("condition")
00030 , action("action", milliseconds(100) )
00031 {
00032 root.addChild(&condition);
00033 root.addChild(&action);
00034 }
00035 ~SimpleFallbackTest()
00036 {
00037 haltAllActions(&root);
00038 }
00039 };
00040
00041 struct ReactiveFallbackTest : testing::Test
00042 {
00043 BT::ReactiveFallback root;
00044 BT::ConditionTestNode condition_1;
00045 BT::ConditionTestNode condition_2;
00046 BT::AsyncActionTest action_1;
00047
00048 ReactiveFallbackTest()
00049 : root("root_first")
00050 , condition_1("condition_1")
00051 , condition_2("condition_2")
00052 , action_1("action_1", milliseconds(100) )
00053 {
00054 root.addChild(&condition_1);
00055 root.addChild(&condition_2);
00056 root.addChild(&action_1);
00057 }
00058 ~ReactiveFallbackTest()
00059 {
00060 haltAllActions(&root);
00061 }
00062 };
00063
00064 struct SimpleFallbackWithMemoryTest : testing::Test
00065 {
00066 BT::FallbackNode root;
00067 BT::AsyncActionTest action;
00068 BT::ConditionTestNode condition;
00069
00070 SimpleFallbackWithMemoryTest() :
00071 root("root_sequence")
00072 , action("action", milliseconds(100) )
00073 , condition("condition")
00074 {
00075 root.addChild(&condition);
00076 root.addChild(&action);
00077 }
00078 ~SimpleFallbackWithMemoryTest()
00079 {
00080 haltAllActions(&root);
00081 }
00082 };
00083
00084 struct ComplexFallbackWithMemoryTest : testing::Test
00085 {
00086 BT::FallbackNode root;
00087
00088 BT::AsyncActionTest action_1;
00089 BT::AsyncActionTest action_2;
00090
00091 BT::ConditionTestNode condition_1;
00092 BT::ConditionTestNode condition_2;
00093
00094 BT::FallbackNode fal_conditions;
00095 BT::FallbackNode fal_actions;
00096
00097 ComplexFallbackWithMemoryTest()
00098 : root("root_fallback")
00099 , action_1("action_1", milliseconds(100) )
00100 , action_2("action_2", milliseconds(100) )
00101 , condition_1("condition_1")
00102 , condition_2("condition_2")
00103 , fal_conditions("fallback_conditions")
00104 , fal_actions("fallback_actions")
00105 {
00106 root.addChild(&fal_conditions);
00107 {
00108 fal_conditions.addChild(&condition_1);
00109 fal_conditions.addChild(&condition_2);
00110 }
00111 root.addChild(&fal_actions);
00112 {
00113 fal_actions.addChild(&action_1);
00114 fal_actions.addChild(&action_2);
00115 }
00116 }
00117 ~ComplexFallbackWithMemoryTest()
00118 {
00119 haltAllActions(&root);
00120 }
00121 };
00122
00123
00124
00125 TEST_F(SimpleFallbackTest, ConditionTrue)
00126 {
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, ConditionChangeWhileRunning)
00137 {
00138 BT::NodeStatus state = BT::NodeStatus::IDLE;
00139
00140 condition.setBoolean(false);
00141 state = root.executeTick();
00142
00143 ASSERT_EQ(NodeStatus::RUNNING, state);
00144 ASSERT_EQ(NodeStatus::FAILURE, condition.status());
00145 ASSERT_EQ(NodeStatus::RUNNING, action.status());
00146
00147 condition.setBoolean(true);
00148 state = root.executeTick();
00149
00150 ASSERT_EQ(NodeStatus::RUNNING, state);
00151 ASSERT_EQ(NodeStatus::FAILURE, condition.status());
00152 ASSERT_EQ(NodeStatus::RUNNING, action.status());
00153 }
00154
00155 TEST_F(ReactiveFallbackTest, Condition1ToTrue)
00156 {
00157 condition_1.setBoolean(false);
00158 condition_2.setBoolean(false);
00159
00160 BT::NodeStatus state = root.executeTick();
00161
00162 ASSERT_EQ(NodeStatus::RUNNING, state);
00163 ASSERT_EQ(NodeStatus::FAILURE, condition_1.status());
00164 ASSERT_EQ(NodeStatus::FAILURE, condition_2.status());
00165 ASSERT_EQ(NodeStatus::RUNNING, action_1.status());
00166
00167 condition_1.setBoolean(true);
00168
00169 state = root.executeTick();
00170
00171 ASSERT_EQ(NodeStatus::SUCCESS, state);
00172 ASSERT_EQ(NodeStatus::IDLE, condition_1.status());
00173 ASSERT_EQ(NodeStatus::IDLE, condition_2.status());
00174 ASSERT_EQ(NodeStatus::IDLE, action_1.status());
00175 }
00176
00177 TEST_F(ReactiveFallbackTest, Condition2ToTrue)
00178 {
00179 condition_1.setBoolean(false);
00180 condition_2.setBoolean(false);
00181
00182 BT::NodeStatus state = root.executeTick();
00183
00184 ASSERT_EQ(NodeStatus::RUNNING, state);
00185 ASSERT_EQ(NodeStatus::FAILURE, condition_1.status());
00186 ASSERT_EQ(NodeStatus::FAILURE, condition_2.status());
00187 ASSERT_EQ(NodeStatus::RUNNING, action_1.status());
00188
00189 condition_2.setBoolean(true);
00190
00191 state = root.executeTick();
00192
00193 ASSERT_EQ(NodeStatus::SUCCESS, state);
00194 ASSERT_EQ(NodeStatus::IDLE, condition_1.status());
00195 ASSERT_EQ(NodeStatus::IDLE, condition_2.status());
00196 ASSERT_EQ(NodeStatus::IDLE, action_1.status());
00197 }
00198
00199 TEST_F(SimpleFallbackWithMemoryTest, ConditionFalse)
00200 {
00201 condition.setBoolean(false);
00202 BT::NodeStatus state = root.executeTick();
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 action_2.setBoolean(true);
00308 condition_1.setBoolean(false);
00309 condition_2.setBoolean(false);
00310
00311 BT::NodeStatus state = root.executeTick();
00312
00313 state = root.executeTick();
00314 std::this_thread::sleep_for(std::chrono::milliseconds(500));
00315 state = root.executeTick();
00316
00317 ASSERT_EQ(NodeStatus::RUNNING, state);
00318 ASSERT_EQ(NodeStatus::FAILURE, fal_conditions.status());
00319 ASSERT_EQ(NodeStatus::IDLE, condition_1.status());
00320 ASSERT_EQ(NodeStatus::IDLE, condition_2.status());
00321 ASSERT_EQ(NodeStatus::RUNNING, fal_actions.status());
00322 ASSERT_EQ(NodeStatus::FAILURE, action_1.status());
00323 ASSERT_EQ(NodeStatus::RUNNING, action_2.status());
00324 }