|
| 1 | + |
| 2 | +/* Copyright (C) 2015-2019 Michele Colledanchise - All Rights Reserved |
| 3 | +* |
| 4 | +* Permission is hereby granted, free of charge, to any person obtaining a copy of this software and associated documentation files (the "Software"), |
| 5 | +* to deal in the Software without restriction, including without limitation the rights to use, copy, modify, merge, publish, distribute, sublicense, |
| 6 | +* 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: |
| 7 | +* The above copyright notice and this permission notice shall be included in all copies or substantial portions of the Software. |
| 8 | +* |
| 9 | +* THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, |
| 10 | +* 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, |
| 11 | +* 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. |
| 12 | +*/ |
| 13 | + |
| 14 | +#include <gtest/gtest.h> |
| 15 | +#include "action_test_node.h" |
| 16 | +#include "condition_test_node.h" |
| 17 | +#include "behaviortree_cpp/behavior_tree.h" |
| 18 | +#include "behaviortree_cpp/loggers/bt_cout_logger.h" |
| 19 | +#include "behaviortree_cpp/bt_factory.h" |
| 20 | + |
| 21 | +using BT::NodeStatus; |
| 22 | +using std::chrono::milliseconds; |
| 23 | + |
| 24 | + |
| 25 | +struct ReactiveFallbackTest : testing::Test |
| 26 | +{ |
| 27 | + BT::ReactiveFallback root; |
| 28 | + BT::ConditionTestNode condition_1; |
| 29 | + BT::ConditionTestNode condition_2; |
| 30 | + BT::AsyncActionTest action_1; |
| 31 | + |
| 32 | + ReactiveFallbackTest() |
| 33 | + : root("root_first") |
| 34 | + , condition_1("condition_1") |
| 35 | + , condition_2("condition_2") |
| 36 | + , action_1("action_1", milliseconds(100) ) |
| 37 | + { |
| 38 | + root.addChild(&condition_1); |
| 39 | + root.addChild(&condition_2); |
| 40 | + root.addChild(&action_1); |
| 41 | + } |
| 42 | + ~ReactiveFallbackTest() |
| 43 | + { |
| 44 | + haltAllActions(&root); |
| 45 | + } |
| 46 | +}; |
| 47 | + |
| 48 | + |
| 49 | +struct ReactiveFallback2ActionsTest : testing::Test |
| 50 | +{ |
| 51 | + BT::ReactiveFallback root; |
| 52 | + BT::AsyncActionTest action_1; |
| 53 | + BT::AsyncActionTest action_2; |
| 54 | + |
| 55 | + ReactiveFallback2ActionsTest() |
| 56 | + : root("root_Fallback") |
| 57 | + , action_1("action_1", milliseconds(100)) |
| 58 | + , action_2("action_2", milliseconds(100)) |
| 59 | + { |
| 60 | + root.addChild(&action_1); |
| 61 | + root.addChild(&action_2); |
| 62 | + } |
| 63 | + ~ReactiveFallback2ActionsTest() |
| 64 | + { |
| 65 | + haltAllActions(&root); |
| 66 | + } |
| 67 | +}; |
| 68 | + |
| 69 | +struct ComplexReactiveFallback2ActionsTest : testing::Test |
| 70 | +{ |
| 71 | + BT::ReactiveFallback root; |
| 72 | + BT::AsyncActionTest action_1; |
| 73 | + BT::AsyncActionTest action_2; |
| 74 | + BT::ReactiveFallback seq_1; |
| 75 | + BT::ReactiveFallback seq_2; |
| 76 | + |
| 77 | + BT::ConditionTestNode condition_1; |
| 78 | + BT::ConditionTestNode condition_2; |
| 79 | + |
| 80 | + ComplexReactiveFallback2ActionsTest() |
| 81 | + : root("root_Fallback") |
| 82 | + , action_1("action_1", milliseconds(100)) |
| 83 | + , action_2("action_2", milliseconds(100)) |
| 84 | + , seq_1("Fallback_1") |
| 85 | + , seq_2("Fallback_2") |
| 86 | + , condition_1("condition_1") |
| 87 | + , condition_2("condition_2") |
| 88 | + { |
| 89 | + root.addChild(&seq_1); |
| 90 | + { |
| 91 | + seq_1.addChild(&condition_1); |
| 92 | + seq_1.addChild(&action_1); |
| 93 | + } |
| 94 | + root.addChild(&seq_2); |
| 95 | + { |
| 96 | + seq_2.addChild(&condition_2); |
| 97 | + seq_2.addChild(&action_2); |
| 98 | + } |
| 99 | + } |
| 100 | + ~ComplexReactiveFallback2ActionsTest() |
| 101 | + { |
| 102 | + haltAllActions(&root); |
| 103 | + } |
| 104 | +}; |
| 105 | + |
| 106 | + |
| 107 | + |
| 108 | +/****************TESTS START HERE***************************/ |
| 109 | + |
| 110 | +TEST_F(ReactiveFallbackTest, Condition1ToTrue) |
| 111 | +{ |
| 112 | + condition_1.setBoolean(false); |
| 113 | + condition_2.setBoolean(false); |
| 114 | + |
| 115 | + BT::NodeStatus state = root.executeTick(); |
| 116 | + |
| 117 | + ASSERT_EQ(NodeStatus::RUNNING, state); |
| 118 | + ASSERT_EQ(NodeStatus::FAILURE, condition_1.status()); |
| 119 | + ASSERT_EQ(NodeStatus::FAILURE, condition_2.status()); |
| 120 | + ASSERT_EQ(NodeStatus::RUNNING, action_1.status()); |
| 121 | + |
| 122 | + condition_1.setBoolean(true); |
| 123 | + |
| 124 | + state = root.executeTick(); |
| 125 | + |
| 126 | + ASSERT_EQ(NodeStatus::SUCCESS, state); |
| 127 | + ASSERT_EQ(NodeStatus::SUCCESS, condition_1.status()); |
| 128 | + ASSERT_EQ(NodeStatus::IDLE, condition_2.status()); |
| 129 | + ASSERT_EQ(NodeStatus::IDLE, action_1.status()); |
| 130 | +} |
| 131 | + |
| 132 | +TEST_F(ReactiveFallbackTest, Condition2ToTrue) |
| 133 | +{ |
| 134 | + condition_1.setBoolean(false); |
| 135 | + condition_2.setBoolean(false); |
| 136 | + |
| 137 | + BT::NodeStatus state = root.executeTick(); |
| 138 | + |
| 139 | + ASSERT_EQ(NodeStatus::RUNNING, state); |
| 140 | + ASSERT_EQ(NodeStatus::FAILURE, condition_1.status()); |
| 141 | + ASSERT_EQ(NodeStatus::FAILURE, condition_2.status()); |
| 142 | + ASSERT_EQ(NodeStatus::RUNNING, action_1.status()); |
| 143 | + |
| 144 | + condition_2.setBoolean(true); |
| 145 | + |
| 146 | + state = root.executeTick(); |
| 147 | + |
| 148 | + ASSERT_EQ(NodeStatus::SUCCESS, state); |
| 149 | + ASSERT_EQ(NodeStatus::FAILURE, condition_1.status()); |
| 150 | + ASSERT_EQ(NodeStatus::SUCCESS, condition_2.status()); |
| 151 | + ASSERT_EQ(NodeStatus::IDLE, action_1.status()); |
| 152 | +} |
| 153 | + |
| 154 | +TEST_F(ReactiveFallback2ActionsTest, Actions) |
| 155 | +{ |
| 156 | + |
| 157 | + root.executeTick(); |
| 158 | + |
| 159 | + ASSERT_EQ(NodeStatus::RUNNING, root.status()); |
| 160 | + ASSERT_EQ(NodeStatus::RUNNING, action_1.status()); |
| 161 | + ASSERT_EQ(NodeStatus::IDLE, action_2.status()); |
| 162 | + |
| 163 | + std::this_thread::sleep_for(milliseconds(1000)); |
| 164 | + |
| 165 | + ASSERT_EQ(NodeStatus::SUCCESS, action_1.status()); |
| 166 | + |
| 167 | + root.executeTick(); |
| 168 | + |
| 169 | + ASSERT_EQ(NodeStatus::SUCCESS, root.status()); |
| 170 | + ASSERT_EQ(NodeStatus::IDLE, action_1.status()); |
| 171 | + ASSERT_EQ(NodeStatus::IDLE, action_2.status()); |
| 172 | + |
| 173 | + root.executeTick(); |
| 174 | + |
| 175 | + ASSERT_EQ(NodeStatus::RUNNING, root.status()); |
| 176 | + ASSERT_EQ(NodeStatus::RUNNING, action_1.status()); |
| 177 | + ASSERT_EQ(NodeStatus::IDLE, action_2.status()); |
| 178 | + |
| 179 | +} |
| 180 | + |
| 181 | + |
| 182 | + |
| 183 | +TEST_F(ComplexReactiveFallback2ActionsTest, ConditionsTrue) |
| 184 | +{ |
| 185 | + BT::NodeStatus state = root.executeTick(); |
| 186 | + |
| 187 | + state = root.executeTick(); |
| 188 | + |
| 189 | + ASSERT_EQ(NodeStatus::SUCCESS, state); |
| 190 | + ASSERT_EQ(NodeStatus::SUCCESS, seq_1.status()); |
| 191 | + ASSERT_EQ(NodeStatus::SUCCESS, condition_1.status()); |
| 192 | + ASSERT_EQ(NodeStatus::IDLE, action_1.status()); |
| 193 | + ASSERT_EQ(NodeStatus::IDLE, seq_2.status()); |
| 194 | + ASSERT_EQ(NodeStatus::IDLE, condition_2.status()); |
| 195 | + ASSERT_EQ(NodeStatus::IDLE, action_2.status()); |
| 196 | + |
| 197 | + std::this_thread::sleep_for(milliseconds(300)); |
| 198 | + state = root.executeTick(); |
| 199 | + |
| 200 | + ASSERT_EQ(NodeStatus::SUCCESS, state); |
| 201 | + ASSERT_EQ(NodeStatus::SUCCESS, seq_1.status()); |
| 202 | + ASSERT_EQ(NodeStatus::SUCCESS, condition_1.status()); |
| 203 | + ASSERT_EQ(NodeStatus::IDLE, action_1.status()); |
| 204 | + ASSERT_EQ(NodeStatus::IDLE, seq_2.status()); |
| 205 | + ASSERT_EQ(NodeStatus::IDLE, condition_2.status()); |
| 206 | + ASSERT_EQ(NodeStatus::IDLE, action_2.status()); |
| 207 | + |
| 208 | + |
| 209 | + std::this_thread::sleep_for(milliseconds(300)); |
| 210 | + state = root.executeTick(); |
| 211 | + |
| 212 | + ASSERT_EQ(NodeStatus::SUCCESS, state); |
| 213 | + ASSERT_EQ(NodeStatus::SUCCESS, seq_1.status()); |
| 214 | + ASSERT_EQ(NodeStatus::SUCCESS, condition_1.status()); |
| 215 | + ASSERT_EQ(NodeStatus::IDLE, action_1.status()); |
| 216 | + ASSERT_EQ(NodeStatus::IDLE, seq_2.status()); |
| 217 | + ASSERT_EQ(NodeStatus::IDLE, condition_2.status()); |
| 218 | + ASSERT_EQ(NodeStatus::IDLE, action_2.status()); |
| 219 | +} |
| 220 | + |
| 221 | + |
| 222 | + |
0 commit comments