|
| 1 | +/* Copyright (C) 2015-2017 Michele Colledanchise - All Rights Reserved |
| 2 | +* |
| 3 | +* Permission is hereby granted, free of charge, to any person obtaining a copy of this software and associated documentation files (the "Software"), |
| 4 | +* to deal in the Software without restriction, including without limitation the rights to use, copy, modify, merge, publish, distribute, sublicense, |
| 5 | +* and/or sell copies of the Software, and to permit persons to whom the Software is furnished to do so, subject to the following conditions: |
| 6 | +* The above copyright notice and this permission notice shall be included in all copies or substantial portions of the Software. |
| 7 | +* |
| 8 | +* THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, |
| 9 | +* FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER LIABILITY, |
| 10 | +* WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE SOFTWARE. |
| 11 | +*/ |
| 12 | + |
| 13 | +#include <gtest/gtest.h> |
| 14 | +#include "action_test_node.h" |
| 15 | +#include "condition_test_node.h" |
| 16 | +#include "behavior_tree_core/behavior_tree.h" |
| 17 | + |
| 18 | +using BT::NodeStatus; |
| 19 | + |
| 20 | + |
| 21 | +struct SimpleFallbackTest : testing::Test |
| 22 | +{ |
| 23 | + BT::FallbackNode root; |
| 24 | + BT::AsyncActionTest action; |
| 25 | + BT::ConditionTestNode condition; |
| 26 | + |
| 27 | + SimpleFallbackTest() : root("root_fallback"), action("action"), condition("condition") |
| 28 | + { |
| 29 | + root.addChild(&condition); |
| 30 | + root.addChild(&action); |
| 31 | + } |
| 32 | + ~SimpleFallbackTest() |
| 33 | + { |
| 34 | + haltAllActions(&root); |
| 35 | + } |
| 36 | +}; |
| 37 | + |
| 38 | +struct ComplexFallbackTest : testing::Test |
| 39 | +{ |
| 40 | + BT::FallbackNode root; |
| 41 | + BT::AsyncActionTest action_1; |
| 42 | + BT::ConditionTestNode condition_1; |
| 43 | + BT::ConditionTestNode condition_2; |
| 44 | + |
| 45 | + BT::FallbackNode fal_conditions; |
| 46 | + |
| 47 | + ComplexFallbackTest() |
| 48 | + : root("root_fallback") |
| 49 | + , action_1("action_1") |
| 50 | + , condition_1("condition_1") |
| 51 | + , condition_2("condition_2") |
| 52 | + , fal_conditions("fallback_conditions") |
| 53 | + { |
| 54 | + root.addChild(&fal_conditions); |
| 55 | + { |
| 56 | + fal_conditions.addChild(&condition_1); |
| 57 | + fal_conditions.addChild(&condition_2); |
| 58 | + } |
| 59 | + root.addChild(&action_1); |
| 60 | + } |
| 61 | + ~ComplexFallbackTest() |
| 62 | + { |
| 63 | + haltAllActions(&root); |
| 64 | + } |
| 65 | +}; |
| 66 | + |
| 67 | + |
| 68 | +struct SimpleFallbackWithMemoryTest : testing::Test |
| 69 | +{ |
| 70 | + BT::FallbackNodeWithMemory root; |
| 71 | + BT::AsyncActionTest action; |
| 72 | + BT::ConditionTestNode condition; |
| 73 | + |
| 74 | + SimpleFallbackWithMemoryTest() : root("root_sequence"), action("action"), condition("condition") |
| 75 | + { |
| 76 | + root.addChild(&condition); |
| 77 | + root.addChild(&action); |
| 78 | + } |
| 79 | + ~SimpleFallbackWithMemoryTest() |
| 80 | + { |
| 81 | + haltAllActions(&root); |
| 82 | + } |
| 83 | +}; |
| 84 | + |
| 85 | +struct ComplexFallbackWithMemoryTest : testing::Test |
| 86 | +{ |
| 87 | + BT::FallbackNodeWithMemory root; |
| 88 | + |
| 89 | + BT::AsyncActionTest action_1; |
| 90 | + BT::AsyncActionTest action_2; |
| 91 | + |
| 92 | + BT::ConditionTestNode condition_1; |
| 93 | + BT::ConditionTestNode condition_2; |
| 94 | + |
| 95 | + BT::FallbackNodeWithMemory fal_conditions; |
| 96 | + BT::FallbackNodeWithMemory fal_actions; |
| 97 | + |
| 98 | + ComplexFallbackWithMemoryTest() |
| 99 | + : root("root_fallback") |
| 100 | + , action_1("action_1") |
| 101 | + , action_2("action_2") |
| 102 | + , condition_1("condition_1") |
| 103 | + , condition_2("condition_2") |
| 104 | + , fal_conditions("fallback_conditions") |
| 105 | + , fal_actions("fallback_actions") |
| 106 | + { |
| 107 | + root.addChild(&fal_conditions); |
| 108 | + { |
| 109 | + fal_conditions.addChild(&condition_1); |
| 110 | + fal_conditions.addChild(&condition_2); |
| 111 | + } |
| 112 | + root.addChild(&fal_actions); |
| 113 | + { |
| 114 | + fal_actions.addChild(&action_1); |
| 115 | + fal_actions.addChild(&action_2); |
| 116 | + } |
| 117 | + } |
| 118 | + ~ComplexFallbackWithMemoryTest() |
| 119 | + { |
| 120 | + haltAllActions(&root); |
| 121 | + } |
| 122 | +}; |
| 123 | + |
| 124 | +/****************TESTS START HERE***************************/ |
| 125 | + |
| 126 | +TEST_F(SimpleFallbackTest, ConditionTrue) |
| 127 | +{ |
| 128 | + std::cout << "Ticking the root node !" << std::endl << std::endl; |
| 129 | + // Ticking the root node |
| 130 | + condition.setBoolean(true); |
| 131 | + BT::NodeStatus state = root.executeTick(); |
| 132 | + |
| 133 | + ASSERT_EQ(NodeStatus::SUCCESS, state); |
| 134 | + ASSERT_EQ(NodeStatus::IDLE, condition.status()); |
| 135 | + ASSERT_EQ(NodeStatus::IDLE, action.status()); |
| 136 | +} |
| 137 | + |
| 138 | +TEST_F(SimpleFallbackTest, ConditionToFalse) |
| 139 | +{ |
| 140 | + condition.setBoolean(false); |
| 141 | + |
| 142 | + BT::NodeStatus state = root.executeTick(); |
| 143 | + condition.setBoolean(true); |
| 144 | + |
| 145 | + state = root.executeTick(); |
| 146 | + |
| 147 | + ASSERT_EQ(NodeStatus::SUCCESS, state); |
| 148 | + ASSERT_EQ(NodeStatus::IDLE, condition.status()); |
| 149 | + ASSERT_EQ(NodeStatus::IDLE, action.status()); |
| 150 | +} |
| 151 | + |
| 152 | +TEST_F(ComplexFallbackTest, Condition1ToTrue) |
| 153 | +{ |
| 154 | + condition_1.setBoolean(false); |
| 155 | + condition_2.setBoolean(false); |
| 156 | + |
| 157 | + BT::NodeStatus state = root.executeTick(); |
| 158 | + |
| 159 | + ASSERT_EQ(NodeStatus::RUNNING, state); |
| 160 | + ASSERT_EQ(NodeStatus::FAILURE, fal_conditions.status()); |
| 161 | + ASSERT_EQ(NodeStatus::IDLE, condition_1.status()); |
| 162 | + ASSERT_EQ(NodeStatus::IDLE, condition_2.status()); |
| 163 | + ASSERT_EQ(NodeStatus::RUNNING, action_1.status()); |
| 164 | + |
| 165 | + condition_1.setBoolean(true); |
| 166 | + |
| 167 | + state = root.executeTick(); |
| 168 | + |
| 169 | + ASSERT_EQ(NodeStatus::SUCCESS, state); |
| 170 | + ASSERT_EQ(NodeStatus::IDLE, fal_conditions.status()); |
| 171 | + ASSERT_EQ(NodeStatus::IDLE, condition_1.status()); |
| 172 | + ASSERT_EQ(NodeStatus::IDLE, condition_2.status()); |
| 173 | + ASSERT_EQ(NodeStatus::IDLE, action_1.status()); |
| 174 | +} |
| 175 | + |
| 176 | +TEST_F(ComplexFallbackTest, Condition2ToTrue) |
| 177 | +{ |
| 178 | + condition_1.setBoolean(false); |
| 179 | + condition_2.setBoolean(false); |
| 180 | + |
| 181 | + BT::NodeStatus state = root.executeTick(); |
| 182 | + |
| 183 | + ASSERT_EQ(NodeStatus::RUNNING, state); |
| 184 | + ASSERT_EQ(NodeStatus::FAILURE, fal_conditions.status()); |
| 185 | + ASSERT_EQ(NodeStatus::IDLE, condition_1.status()); |
| 186 | + ASSERT_EQ(NodeStatus::IDLE, condition_2.status()); |
| 187 | + ASSERT_EQ(NodeStatus::RUNNING, action_1.status()); |
| 188 | + |
| 189 | + condition_2.setBoolean(true); |
| 190 | + |
| 191 | + state = root.executeTick(); |
| 192 | + |
| 193 | + ASSERT_EQ(NodeStatus::SUCCESS, state); |
| 194 | + ASSERT_EQ(NodeStatus::IDLE, fal_conditions.status()); |
| 195 | + ASSERT_EQ(NodeStatus::IDLE, condition_1.status()); |
| 196 | + ASSERT_EQ(NodeStatus::IDLE, condition_2.status()); |
| 197 | + ASSERT_EQ(NodeStatus::IDLE, action_1.status()); |
| 198 | +} |
| 199 | + |
| 200 | + |
| 201 | +TEST_F(SimpleFallbackWithMemoryTest, ConditionFalse) |
| 202 | +{ |
| 203 | + condition.setBoolean(false); |
| 204 | + BT::NodeStatus state = root.executeTick(); |
| 205 | + std::this_thread::sleep_for(std::chrono::milliseconds(100)); |
| 206 | + |
| 207 | + ASSERT_EQ(NodeStatus::RUNNING, state); |
| 208 | + ASSERT_EQ(NodeStatus::FAILURE, condition.status()); |
| 209 | + ASSERT_EQ(NodeStatus::RUNNING, action.status()); |
| 210 | +} |
| 211 | + |
| 212 | +TEST_F(SimpleFallbackWithMemoryTest, ConditionTurnToTrue) |
| 213 | +{ |
| 214 | + condition.setBoolean(false); |
| 215 | + BT::NodeStatus state = root.executeTick(); |
| 216 | + |
| 217 | + ASSERT_EQ(NodeStatus::RUNNING, state); |
| 218 | + ASSERT_EQ(NodeStatus::FAILURE, condition.status()); |
| 219 | + ASSERT_EQ(NodeStatus::RUNNING, action.status()); |
| 220 | + |
| 221 | + condition.setBoolean(true); |
| 222 | + state = root.executeTick(); |
| 223 | + |
| 224 | + ASSERT_EQ(NodeStatus::RUNNING, state); |
| 225 | + ASSERT_EQ(NodeStatus::FAILURE, condition.status()); |
| 226 | + ASSERT_EQ(NodeStatus::RUNNING, action.status()); |
| 227 | +} |
| 228 | + |
| 229 | +TEST_F(ComplexFallbackWithMemoryTest, ConditionsTrue) |
| 230 | +{ |
| 231 | + BT::NodeStatus state = root.executeTick(); |
| 232 | + |
| 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()); |
| 240 | +} |
| 241 | + |
| 242 | +TEST_F(ComplexFallbackWithMemoryTest, Condition1False) |
| 243 | +{ |
| 244 | + condition_1.setBoolean(false); |
| 245 | + BT::NodeStatus state = root.executeTick(); |
| 246 | + |
| 247 | + ASSERT_EQ(NodeStatus::SUCCESS, state); |
| 248 | + ASSERT_EQ(NodeStatus::IDLE, fal_conditions.status()); |
| 249 | + ASSERT_EQ(NodeStatus::IDLE, condition_1.status()); |
| 250 | + ASSERT_EQ(NodeStatus::IDLE, condition_2.status()); |
| 251 | + ASSERT_EQ(NodeStatus::IDLE, fal_actions.status()); |
| 252 | + ASSERT_EQ(NodeStatus::IDLE, action_1.status()); |
| 253 | + ASSERT_EQ(NodeStatus::IDLE, action_2.status()); |
| 254 | +} |
| 255 | + |
| 256 | +TEST_F(ComplexFallbackWithMemoryTest, ConditionsFalse) |
| 257 | +{ |
| 258 | + condition_1.setBoolean(false); |
| 259 | + condition_2.setBoolean(false); |
| 260 | + BT::NodeStatus state = root.executeTick(); |
| 261 | + |
| 262 | + ASSERT_EQ(NodeStatus::RUNNING, state); |
| 263 | + ASSERT_EQ(NodeStatus::FAILURE, fal_conditions.status()); |
| 264 | + ASSERT_EQ(NodeStatus::IDLE, condition_1.status()); |
| 265 | + ASSERT_EQ(NodeStatus::IDLE, condition_2.status()); |
| 266 | + ASSERT_EQ(NodeStatus::RUNNING, fal_actions.status()); |
| 267 | + ASSERT_EQ(NodeStatus::RUNNING, action_1.status()); |
| 268 | + ASSERT_EQ(NodeStatus::IDLE, action_2.status()); |
| 269 | +} |
| 270 | + |
| 271 | +TEST_F(ComplexFallbackWithMemoryTest, Conditions1ToTrue) |
| 272 | +{ |
| 273 | + condition_1.setBoolean(false); |
| 274 | + condition_2.setBoolean(false); |
| 275 | + BT::NodeStatus state = root.executeTick(); |
| 276 | + |
| 277 | + condition_1.setBoolean(true); |
| 278 | + state = root.executeTick(); |
| 279 | + |
| 280 | + ASSERT_EQ(NodeStatus::RUNNING, state); |
| 281 | + ASSERT_EQ(NodeStatus::FAILURE, fal_conditions.status()); |
| 282 | + ASSERT_EQ(NodeStatus::IDLE, condition_1.status()); |
| 283 | + ASSERT_EQ(NodeStatus::IDLE, condition_2.status()); |
| 284 | + ASSERT_EQ(NodeStatus::RUNNING, fal_actions.status()); |
| 285 | + ASSERT_EQ(NodeStatus::RUNNING, action_1.status()); |
| 286 | + ASSERT_EQ(NodeStatus::IDLE, action_2.status()); |
| 287 | +} |
| 288 | + |
| 289 | +TEST_F(ComplexFallbackWithMemoryTest, Conditions2ToTrue) |
| 290 | +{ |
| 291 | + condition_1.setBoolean(false); |
| 292 | + condition_2.setBoolean(false); |
| 293 | + BT::NodeStatus state = root.executeTick(); |
| 294 | + |
| 295 | + condition_2.setBoolean(true); |
| 296 | + state = root.executeTick(); |
| 297 | + |
| 298 | + ASSERT_EQ(NodeStatus::RUNNING, state); |
| 299 | + ASSERT_EQ(NodeStatus::FAILURE, fal_conditions.status()); |
| 300 | + ASSERT_EQ(NodeStatus::IDLE, condition_1.status()); |
| 301 | + ASSERT_EQ(NodeStatus::IDLE, condition_2.status()); |
| 302 | + ASSERT_EQ(NodeStatus::RUNNING, fal_actions.status()); |
| 303 | + ASSERT_EQ(NodeStatus::RUNNING, action_1.status()); |
| 304 | + ASSERT_EQ(NodeStatus::IDLE, action_2.status()); |
| 305 | +} |
| 306 | + |
| 307 | +TEST_F(ComplexFallbackWithMemoryTest, Action1Failed) |
| 308 | +{ |
| 309 | + action_1.setBoolean(false); |
| 310 | + condition_1.setBoolean(false); |
| 311 | + condition_2.setBoolean(false); |
| 312 | + |
| 313 | + BT::NodeStatus state = root.executeTick(); |
| 314 | + |
| 315 | + state = root.executeTick(); |
| 316 | + std::this_thread::sleep_for(std::chrono::milliseconds(500)); |
| 317 | + state = root.executeTick(); |
| 318 | + |
| 319 | + ASSERT_EQ(NodeStatus::RUNNING, state); |
| 320 | + ASSERT_EQ(NodeStatus::FAILURE, fal_conditions.status()); |
| 321 | + ASSERT_EQ(NodeStatus::IDLE, condition_1.status()); |
| 322 | + ASSERT_EQ(NodeStatus::IDLE, condition_2.status()); |
| 323 | + ASSERT_EQ(NodeStatus::RUNNING, fal_actions.status()); |
| 324 | + ASSERT_EQ(NodeStatus::FAILURE, action_1.status()); |
| 325 | + ASSERT_EQ(NodeStatus::RUNNING, action_2.status()); |
| 326 | +} |
| 327 | + |
| 328 | + |
0 commit comments