1 #include <gtest/gtest.h> 9 using std::chrono::milliseconds;
13 <root main_tree_to_execute = "MainTree" > 15 <BehaviorTree ID="MainTree"> 16 <Switch3 name="simple_switch" variable="{my_var}" case_1="1" case_2="42 case_3="666" > 17 <AsyncActionTest name="action_1"/> 18 <AsyncActionTest name="action_42"/> 19 <AsyncActionTest name="action_666"/> 20 <AsyncActionTest name="action_default"/> 29 std::unique_ptr<Switch2>
root;
37 action_1(
"action_1", milliseconds(100)),
38 action_42(
"action_42", milliseconds(100)),
39 action_def(
"action_default", milliseconds(100))
42 input.insert(std::make_pair(
"variable",
"{my_var}"));
43 input.insert(std::make_pair(
"case_1",
"1"));
44 input.insert(std::make_pair(
"case_2",
"42"));
52 root->addChild(&action_1);
53 root->addChild(&action_42);
54 root->addChild(&action_def);
69 ASSERT_EQ(NodeStatus::RUNNING, state);
71 std::this_thread::sleep_for(milliseconds(110));
72 state =
root->executeTick();
77 ASSERT_EQ(NodeStatus::SUCCESS, state);
82 bb->set(
"my_var",
"1");
88 ASSERT_EQ(NodeStatus::RUNNING, state);
90 std::this_thread::sleep_for(milliseconds(110));
91 state =
root->executeTick();
96 ASSERT_EQ(NodeStatus::SUCCESS, state);
101 bb->set(
"my_var",
"42");
107 ASSERT_EQ(NodeStatus::RUNNING, state);
109 std::this_thread::sleep_for(milliseconds(110));
110 state =
root->executeTick();
115 ASSERT_EQ(NodeStatus::SUCCESS, state);
120 bb->set(
"my_var",
"none");
126 ASSERT_EQ(NodeStatus::RUNNING, state);
128 std::this_thread::sleep_for(milliseconds(110));
129 state =
root->executeTick();
134 ASSERT_EQ(NodeStatus::SUCCESS, state);
139 bb->set(
"my_var",
"1");
145 ASSERT_EQ(NodeStatus::RUNNING, state);
147 std::this_thread::sleep_for(milliseconds(10));
148 state =
root->executeTick();
152 ASSERT_EQ(NodeStatus::RUNNING, state);
156 std::this_thread::sleep_for(milliseconds(10));
157 bb->set(
"my_var",
"");
158 std::this_thread::sleep_for(milliseconds(10));
162 ASSERT_EQ(NodeStatus::RUNNING,
root->status());
164 std::this_thread::sleep_for(milliseconds(10));
165 state =
root->executeTick();
169 ASSERT_EQ(NodeStatus::RUNNING, state);
171 std::this_thread::sleep_for(milliseconds(110));
172 state =
root->executeTick();
177 ASSERT_EQ(NodeStatus::SUCCESS,
root->status());
182 bb->set(
"my_var",
"1");
188 ASSERT_EQ(NodeStatus::RUNNING, state);
190 bb->set(
"my_var",
"42");
191 std::this_thread::sleep_for(milliseconds(10));
192 state =
root->executeTick();
196 ASSERT_EQ(NodeStatus::RUNNING, state);
198 std::this_thread::sleep_for(milliseconds(110));
199 state =
root->executeTick();
204 ASSERT_EQ(NodeStatus::SUCCESS,
root->status());
209 bb->set(
"my_var",
"1");
217 ASSERT_EQ(NodeStatus::RUNNING, state);
219 std::this_thread::sleep_for(milliseconds(110));
220 state =
root->executeTick();
222 ASSERT_EQ(NodeStatus::FAILURE, state);
static Blackboard::Ptr create(Blackboard::Ptr parent={})
BT::AsyncActionTest action_def
NodeStatus status() const
std::unique_ptr< Switch2 > root
std::shared_ptr< Blackboard > Ptr
Blackboard::Ptr blackboard
BT::NodeConfiguration simple_switch_config_
BT::AsyncActionTest action_42
BT::AsyncActionTest action_1
The SwitchNode is equivalent to a switch statement, where a certain branch (child) is executed accord...
TEST_F(SwitchTest, DefaultCase)
static const char * xml_text
void setExpectedResult(NodeStatus res)
PortsRemapping input_ports
std::unordered_map< std::string, std::string > PortsRemapping