gtest_switch.cpp
Go to the documentation of this file.
1 #include <gtest/gtest.h>
2 #include "action_test_node.h"
3 #include "condition_test_node.h"
7 
8 using BT::NodeStatus;
9 using std::chrono::milliseconds;
10 
11 static const char* xml_text = R"(
12 
13 <root main_tree_to_execute = "MainTree" >
14 
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"/>
21  </Switch3>
22  </BehaviorTree>
23 </root>
24  )";
25 
26 struct SwitchTest : testing::Test
27 {
29  std::unique_ptr<Switch2> root;
35 
37  action_1("action_1", milliseconds(100)),
38  action_42("action_42", milliseconds(100)),
39  action_def("action_default", milliseconds(100))
40  {
41  BT::PortsRemapping input;
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"));
45 
47  simple_switch_config_.blackboard = bb;
48  simple_switch_config_.input_ports = input;
49 
50  root = std::make_unique<Switch2>("simple_switch", simple_switch_config_);
51 
52  root->addChild(&action_1);
53  root->addChild(&action_42);
54  root->addChild(&action_def);
55  }
57  {
58  root->halt();
59  }
60 };
61 
62 TEST_F(SwitchTest, DefaultCase)
63 {
64  BT::NodeStatus state = root->executeTick();
65 
66  ASSERT_EQ(NodeStatus::IDLE, action_1.status());
67  ASSERT_EQ(NodeStatus::IDLE, action_42.status());
68  ASSERT_EQ(NodeStatus::RUNNING, action_def.status());
69  ASSERT_EQ(NodeStatus::RUNNING, state);
70 
71  std::this_thread::sleep_for(milliseconds(110));
72  state = root->executeTick();
73 
74  ASSERT_EQ(NodeStatus::IDLE, action_1.status());
75  ASSERT_EQ(NodeStatus::IDLE, action_42.status());
76  ASSERT_EQ(NodeStatus::IDLE, action_def.status());
77  ASSERT_EQ(NodeStatus::SUCCESS, state);
78 }
79 
81 {
82  bb->set("my_var", "1");
83  BT::NodeStatus state = root->executeTick();
84 
85  ASSERT_EQ(NodeStatus::RUNNING, action_1.status());
86  ASSERT_EQ(NodeStatus::IDLE, action_42.status());
87  ASSERT_EQ(NodeStatus::IDLE, action_def.status());
88  ASSERT_EQ(NodeStatus::RUNNING, state);
89 
90  std::this_thread::sleep_for(milliseconds(110));
91  state = root->executeTick();
92 
93  ASSERT_EQ(NodeStatus::IDLE, action_1.status());
94  ASSERT_EQ(NodeStatus::IDLE, action_42.status());
95  ASSERT_EQ(NodeStatus::IDLE, action_def.status());
96  ASSERT_EQ(NodeStatus::SUCCESS, state);
97 }
98 
100 {
101  bb->set("my_var", "42");
102  BT::NodeStatus state = root->executeTick();
103 
104  ASSERT_EQ(NodeStatus::IDLE, action_1.status());
105  ASSERT_EQ(NodeStatus::RUNNING, action_42.status());
106  ASSERT_EQ(NodeStatus::IDLE, action_def.status());
107  ASSERT_EQ(NodeStatus::RUNNING, state);
108 
109  std::this_thread::sleep_for(milliseconds(110));
110  state = root->executeTick();
111 
112  ASSERT_EQ(NodeStatus::IDLE, action_1.status());
113  ASSERT_EQ(NodeStatus::IDLE, action_42.status());
114  ASSERT_EQ(NodeStatus::IDLE, action_def.status());
115  ASSERT_EQ(NodeStatus::SUCCESS, state);
116 }
117 
118 TEST_F(SwitchTest, CaseNone)
119 {
120  bb->set("my_var", "none");
121  BT::NodeStatus state = root->executeTick();
122 
123  ASSERT_EQ(NodeStatus::IDLE, action_1.status());
124  ASSERT_EQ(NodeStatus::IDLE, action_42.status());
125  ASSERT_EQ(NodeStatus::RUNNING, action_def.status());
126  ASSERT_EQ(NodeStatus::RUNNING, state);
127 
128  std::this_thread::sleep_for(milliseconds(110));
129  state = root->executeTick();
130 
131  ASSERT_EQ(NodeStatus::IDLE, action_1.status());
132  ASSERT_EQ(NodeStatus::IDLE, action_42.status());
133  ASSERT_EQ(NodeStatus::IDLE, action_def.status());
134  ASSERT_EQ(NodeStatus::SUCCESS, state);
135 }
136 
137 TEST_F(SwitchTest, CaseSwitchToDefault)
138 {
139  bb->set("my_var", "1");
140  BT::NodeStatus state = root->executeTick();
141 
142  ASSERT_EQ(NodeStatus::RUNNING, action_1.status());
143  ASSERT_EQ(NodeStatus::IDLE, action_42.status());
144  ASSERT_EQ(NodeStatus::IDLE, action_def.status());
145  ASSERT_EQ(NodeStatus::RUNNING, state);
146 
147  std::this_thread::sleep_for(milliseconds(10));
148  state = root->executeTick();
149  ASSERT_EQ(NodeStatus::RUNNING, action_1.status());
150  ASSERT_EQ(NodeStatus::IDLE, action_42.status());
151  ASSERT_EQ(NodeStatus::IDLE, action_def.status());
152  ASSERT_EQ(NodeStatus::RUNNING, state);
153 
154  // Switch Node does not feels changes. Only when tick.
155  // (not reactive)
156  std::this_thread::sleep_for(milliseconds(10));
157  bb->set("my_var", "");
158  std::this_thread::sleep_for(milliseconds(10));
159  ASSERT_EQ(NodeStatus::RUNNING, action_1.status());
160  ASSERT_EQ(NodeStatus::IDLE, action_42.status());
161  ASSERT_EQ(NodeStatus::IDLE, action_def.status());
162  ASSERT_EQ(NodeStatus::RUNNING, root->status());
163 
164  std::this_thread::sleep_for(milliseconds(10));
165  state = root->executeTick();
166  ASSERT_EQ(NodeStatus::IDLE, action_1.status());
167  ASSERT_EQ(NodeStatus::IDLE, action_42.status());
168  ASSERT_EQ(NodeStatus::RUNNING, action_def.status());
169  ASSERT_EQ(NodeStatus::RUNNING, state);
170 
171  std::this_thread::sleep_for(milliseconds(110));
172  state = root->executeTick();
173 
174  ASSERT_EQ(NodeStatus::IDLE, action_1.status());
175  ASSERT_EQ(NodeStatus::IDLE, action_42.status());
176  ASSERT_EQ(NodeStatus::IDLE, action_def.status());
177  ASSERT_EQ(NodeStatus::SUCCESS, root->status());
178 }
179 
180 TEST_F(SwitchTest, CaseSwitchToAction2)
181 {
182  bb->set("my_var", "1");
183  BT::NodeStatus state = root->executeTick();
184 
185  ASSERT_EQ(NodeStatus::RUNNING, action_1.status());
186  ASSERT_EQ(NodeStatus::IDLE, action_42.status());
187  ASSERT_EQ(NodeStatus::IDLE, action_def.status());
188  ASSERT_EQ(NodeStatus::RUNNING, state);
189 
190  bb->set("my_var", "42");
191  std::this_thread::sleep_for(milliseconds(10));
192  state = root->executeTick();
193  ASSERT_EQ(NodeStatus::IDLE, action_1.status());
194  ASSERT_EQ(NodeStatus::RUNNING, action_42.status());
195  ASSERT_EQ(NodeStatus::IDLE, action_def.status());
196  ASSERT_EQ(NodeStatus::RUNNING, state);
197 
198  std::this_thread::sleep_for(milliseconds(110));
199  state = root->executeTick();
200 
201  ASSERT_EQ(NodeStatus::IDLE, action_1.status());
202  ASSERT_EQ(NodeStatus::IDLE, action_42.status());
203  ASSERT_EQ(NodeStatus::IDLE, action_def.status());
204  ASSERT_EQ(NodeStatus::SUCCESS, root->status());
205 }
206 
207 TEST_F(SwitchTest, ActionFailure)
208 {
209  bb->set("my_var", "1");
210  BT::NodeStatus state = root->executeTick();
211 
212  action_1.setExpectedResult(NodeStatus::FAILURE);
213 
214  ASSERT_EQ(NodeStatus::RUNNING, action_1.status());
215  ASSERT_EQ(NodeStatus::IDLE, action_42.status());
216  ASSERT_EQ(NodeStatus::IDLE, action_def.status());
217  ASSERT_EQ(NodeStatus::RUNNING, state);
218 
219  std::this_thread::sleep_for(milliseconds(110));
220  state = root->executeTick();
221 
222  ASSERT_EQ(NodeStatus::FAILURE, state);
223  ASSERT_EQ(NodeStatus::IDLE, action_1.status());
224  ASSERT_EQ(NodeStatus::IDLE, action_42.status());
225  ASSERT_EQ(NodeStatus::IDLE, action_def.status());
226 }
static Blackboard::Ptr create(Blackboard::Ptr parent={})
Definition: blackboard.h:38
BT::AsyncActionTest action_def
BT::Blackboard::Ptr bb
std::unique_ptr< Switch2 > root
std::shared_ptr< Blackboard > Ptr
Definition: blackboard.h:26
Blackboard::Ptr blackboard
Definition: tree_node.h:47
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...
Definition: switch_node.h:44
NodeStatus status() const
Definition: tree_node.cpp:56
TEST_F(SwitchTest, DefaultCase)
static const char * xml_text
NodeStatus
Definition: basic_types.h:35
void setExpectedResult(NodeStatus res)
PortsRemapping input_ports
Definition: tree_node.h:48
std::unordered_map< std::string, std::string > PortsRemapping
Definition: tree_node.h:39


behaviotree_cpp_v3
Author(s): Michele Colledanchise, Davide Faconti
autogenerated on Tue May 4 2021 02:56:25