1
+ #include < gtest/gtest.h>
2
+ #include " action_test_node.h"
3
+ #include " condition_test_node.h"
4
+ #include " behaviortree_cpp_v3/behavior_tree.h"
5
+ #include " behaviortree_cpp_v3/tree_node.h"
6
+
7
+ using BT::NodeStatus;
8
+ using std::chrono::milliseconds;
9
+
10
+ struct SwitchTest : testing::Test
11
+ {
12
+
13
+ std::unique_ptr<BT::SwitchNode<2 >> root;
14
+ BT::AsyncActionTest action_1;
15
+ BT::AsyncActionTest action_2;
16
+ BT::AsyncActionTest action_3;
17
+ BT::Blackboard::Ptr bb = BT::Blackboard::create();
18
+ BT::NodeConfiguration simple_switch_config_;
19
+
20
+ SwitchTest () :
21
+ action_1(" action_1" , milliseconds(100 )),
22
+ action_2(" action_2" , milliseconds(100 )),
23
+ action_3(" action_3" , milliseconds(100 ))
24
+ {
25
+ BT::PortsRemapping input;
26
+ input.insert (std::make_pair (" case_1" , " 1" ));
27
+ input.insert (std::make_pair (" case_2" , " 2" ));
28
+
29
+ BT::NodeConfiguration simple_switch_config_;
30
+ simple_switch_config_.blackboard = bb;
31
+ simple_switch_config_.input_ports = input;
32
+
33
+ root = std::make_unique<BT::SwitchNode<2 >>
34
+ (" simple_switch" , simple_switch_config_);
35
+ root->addChild (&action_1);
36
+ root->addChild (&action_2);
37
+ root->addChild (&action_3);
38
+ }
39
+ ~SwitchTest ()
40
+ {
41
+ root->halt ();
42
+ }
43
+ };
44
+
45
+ TEST_F (SwitchTest, DefaultCase)
46
+ {
47
+ BT::NodeStatus state = root->executeTick ();
48
+
49
+ ASSERT_EQ (NodeStatus::IDLE, action_1.status ());
50
+ ASSERT_EQ (NodeStatus::IDLE, action_2.status ());
51
+ ASSERT_EQ (NodeStatus::RUNNING, action_3.status ());
52
+ ASSERT_EQ (NodeStatus::RUNNING, state);
53
+
54
+ std::this_thread::sleep_for (milliseconds (110 ));
55
+ state = root->executeTick ();
56
+
57
+ ASSERT_EQ (NodeStatus::IDLE, action_1.status ());
58
+ ASSERT_EQ (NodeStatus::IDLE, action_2.status ());
59
+ ASSERT_EQ (NodeStatus::IDLE, action_3.status ());
60
+ ASSERT_EQ (NodeStatus::SUCCESS, state);
61
+ }
62
+
63
+ TEST_F (SwitchTest, Case1)
64
+ {
65
+ bb->set (" variable" , " 1" );
66
+ BT::NodeStatus state = root->executeTick ();
67
+
68
+ ASSERT_EQ (NodeStatus::RUNNING, action_1.status ());
69
+ ASSERT_EQ (NodeStatus::IDLE, action_2.status ());
70
+ ASSERT_EQ (NodeStatus::IDLE, action_3.status ());
71
+ ASSERT_EQ (NodeStatus::RUNNING, state);
72
+
73
+ std::this_thread::sleep_for (milliseconds (110 ));
74
+ state = root->executeTick ();
75
+
76
+ ASSERT_EQ (NodeStatus::IDLE, action_1.status ());
77
+ ASSERT_EQ (NodeStatus::IDLE, action_2.status ());
78
+ ASSERT_EQ (NodeStatus::IDLE, action_3.status ());
79
+ ASSERT_EQ (NodeStatus::SUCCESS, state);
80
+ }
81
+
82
+ TEST_F (SwitchTest, Case2)
83
+ {
84
+ bb->set (" variable" , " 2" );
85
+ BT::NodeStatus state = root->executeTick ();
86
+
87
+ ASSERT_EQ (NodeStatus::IDLE, action_1.status ());
88
+ ASSERT_EQ (NodeStatus::RUNNING, action_2.status ());
89
+ ASSERT_EQ (NodeStatus::IDLE, action_3.status ());
90
+ ASSERT_EQ (NodeStatus::RUNNING, state);
91
+
92
+ std::this_thread::sleep_for (milliseconds (110 ));
93
+ state = root->executeTick ();
94
+
95
+ ASSERT_EQ (NodeStatus::IDLE, action_1.status ());
96
+ ASSERT_EQ (NodeStatus::IDLE, action_2.status ());
97
+ ASSERT_EQ (NodeStatus::IDLE, action_3.status ());
98
+ ASSERT_EQ (NodeStatus::SUCCESS, state);
99
+ }
100
+
101
+ TEST_F (SwitchTest, CaseNone)
102
+ {
103
+ bb->set (" variable" , " none" );
104
+ BT::NodeStatus state = root->executeTick ();
105
+
106
+ ASSERT_EQ (NodeStatus::IDLE, action_1.status ());
107
+ ASSERT_EQ (NodeStatus::IDLE, action_2.status ());
108
+ ASSERT_EQ (NodeStatus::RUNNING, action_3.status ());
109
+ ASSERT_EQ (NodeStatus::RUNNING, state);
110
+
111
+ std::this_thread::sleep_for (milliseconds (110 ));
112
+ state = root->executeTick ();
113
+
114
+ ASSERT_EQ (NodeStatus::IDLE, action_1.status ());
115
+ ASSERT_EQ (NodeStatus::IDLE, action_2.status ());
116
+ ASSERT_EQ (NodeStatus::IDLE, action_3.status ());
117
+ ASSERT_EQ (NodeStatus::SUCCESS, state);
118
+ }
119
+
120
+ TEST_F (SwitchTest, CaseSwitchToDefault)
121
+ {
122
+ bb->set (" variable" , " 1" );
123
+ BT::NodeStatus state = root->executeTick ();
124
+
125
+ ASSERT_EQ (NodeStatus::RUNNING, action_1.status ());
126
+ ASSERT_EQ (NodeStatus::IDLE, action_2.status ());
127
+ ASSERT_EQ (NodeStatus::IDLE, action_3.status ());
128
+ ASSERT_EQ (NodeStatus::RUNNING, state);
129
+
130
+ std::this_thread::sleep_for (milliseconds (10 ));
131
+ state = root->executeTick ();
132
+ ASSERT_EQ (NodeStatus::RUNNING, action_1.status ());
133
+ ASSERT_EQ (NodeStatus::IDLE, action_2.status ());
134
+ ASSERT_EQ (NodeStatus::IDLE, action_3.status ());
135
+ ASSERT_EQ (NodeStatus::RUNNING, state);
136
+
137
+ // Switch Node does not feels changes. Only when tick.
138
+ // (not reactive)
139
+ std::this_thread::sleep_for (milliseconds (10 ));
140
+ bb->set (" variable" , " " );
141
+ std::this_thread::sleep_for (milliseconds (10 ));
142
+ ASSERT_EQ (NodeStatus::RUNNING, action_1.status ());
143
+ ASSERT_EQ (NodeStatus::IDLE, action_2.status ());
144
+ ASSERT_EQ (NodeStatus::IDLE, action_3.status ());
145
+ ASSERT_EQ (NodeStatus::RUNNING, root->status ());
146
+
147
+ std::this_thread::sleep_for (milliseconds (10 ));
148
+ state = root->executeTick ();
149
+ ASSERT_EQ (NodeStatus::IDLE, action_1.status ());
150
+ ASSERT_EQ (NodeStatus::IDLE, action_2.status ());
151
+ ASSERT_EQ (NodeStatus::RUNNING, action_3.status ());
152
+ ASSERT_EQ (NodeStatus::RUNNING, state);
153
+
154
+ std::this_thread::sleep_for (milliseconds (110 ));
155
+ state = root->executeTick ();
156
+
157
+ ASSERT_EQ (NodeStatus::IDLE, action_1.status ());
158
+ ASSERT_EQ (NodeStatus::IDLE, action_2.status ());
159
+ ASSERT_EQ (NodeStatus::IDLE, action_3.status ());
160
+ ASSERT_EQ (NodeStatus::SUCCESS, root->status ());
161
+ }
162
+
163
+ TEST_F (SwitchTest, CaseSwitchToAction2)
164
+ {
165
+ bb->set (" variable" , " 1" );
166
+ BT::NodeStatus state = root->executeTick ();
167
+
168
+ ASSERT_EQ (NodeStatus::RUNNING, action_1.status ());
169
+ ASSERT_EQ (NodeStatus::IDLE, action_2.status ());
170
+ ASSERT_EQ (NodeStatus::IDLE, action_3.status ());
171
+ ASSERT_EQ (NodeStatus::RUNNING, state);
172
+
173
+ bb->set (" variable" , " 2" );
174
+ std::this_thread::sleep_for (milliseconds (10 ));
175
+ state = root->executeTick ();
176
+ ASSERT_EQ (NodeStatus::IDLE, action_1.status ());
177
+ ASSERT_EQ (NodeStatus::RUNNING, action_2.status ());
178
+ ASSERT_EQ (NodeStatus::IDLE, action_3.status ());
179
+ ASSERT_EQ (NodeStatus::RUNNING, state);
180
+
181
+ std::this_thread::sleep_for (milliseconds (110 ));
182
+ state = root->executeTick ();
183
+
184
+ ASSERT_EQ (NodeStatus::IDLE, action_1.status ());
185
+ ASSERT_EQ (NodeStatus::IDLE, action_2.status ());
186
+ ASSERT_EQ (NodeStatus::IDLE, action_3.status ());
187
+ ASSERT_EQ (NodeStatus::SUCCESS, root->status ());
188
+ }
189
+
190
+ TEST_F (SwitchTest, ActionFailure)
191
+ {
192
+ bb->set (" variable" , " 1" );
193
+ BT::NodeStatus state = root->executeTick ();
194
+
195
+ ASSERT_EQ (NodeStatus::RUNNING, action_1.status ());
196
+ ASSERT_EQ (NodeStatus::IDLE, action_2.status ());
197
+ ASSERT_EQ (NodeStatus::IDLE, action_3.status ());
198
+ ASSERT_EQ (NodeStatus::RUNNING, state);
199
+
200
+ std::this_thread::sleep_for (milliseconds (10 ));
201
+ action_1.setStatus (NodeStatus::FAILURE);
202
+ state = root->executeTick ();
203
+ ASSERT_EQ (NodeStatus::FAILURE, action_1.status ());
204
+ ASSERT_EQ (NodeStatus::IDLE, action_2.status ());
205
+ ASSERT_EQ (NodeStatus::IDLE, action_3.status ());
206
+ ASSERT_EQ (NodeStatus::IDLE, state);
207
+
208
+ state = root->executeTick ();
209
+ state = root->executeTick ();
210
+ ASSERT_EQ (NodeStatus::FAILURE, action_1.status ());
211
+ ASSERT_EQ (NodeStatus::IDLE, action_2.status ());
212
+ ASSERT_EQ (NodeStatus::IDLE, action_3.status ());
213
+ ASSERT_EQ (NodeStatus::IDLE, state);
214
+ }
0 commit comments