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
+
56
+ // Switch Node does not halt action after success ?
57
+ ASSERT_EQ (NodeStatus::IDLE, action_1.status ());
58
+ ASSERT_EQ (NodeStatus::IDLE, action_2.status ());
59
+ ASSERT_EQ (NodeStatus::SUCCESS, 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
+
75
+ ASSERT_EQ (NodeStatus::SUCCESS, action_1.status ());
76
+ ASSERT_EQ (NodeStatus::IDLE, action_2.status ());
77
+ ASSERT_EQ (NodeStatus::IDLE, action_3.status ());
78
+ ASSERT_EQ (NodeStatus::SUCCESS, state);
79
+ }
80
+
81
+ TEST_F (SwitchTest, Case2)
82
+ {
83
+ bb->set (" variable" , " 2" );
84
+ BT::NodeStatus state = root->executeTick ();
85
+
86
+ ASSERT_EQ (NodeStatus::IDLE, action_1.status ());
87
+ ASSERT_EQ (NodeStatus::RUNNING, action_2.status ());
88
+ ASSERT_EQ (NodeStatus::IDLE, action_3.status ());
89
+ ASSERT_EQ (NodeStatus::RUNNING, state);
90
+
91
+ std::this_thread::sleep_for (milliseconds (110 ));
92
+
93
+ ASSERT_EQ (NodeStatus::IDLE, action_1.status ());
94
+ ASSERT_EQ (NodeStatus::SUCCESS, action_2.status ());
95
+ ASSERT_EQ (NodeStatus::IDLE, action_3.status ());
96
+ ASSERT_EQ (NodeStatus::SUCCESS, state);
97
+ }
98
+
99
+ TEST_F (SwitchTest, CaseNone)
100
+ {
101
+ bb->set (" variable" , " none" );
102
+ BT::NodeStatus state = root->executeTick ();
103
+
104
+ ASSERT_EQ (NodeStatus::IDLE, action_1.status ());
105
+ ASSERT_EQ (NodeStatus::IDLE, action_2.status ());
106
+ ASSERT_EQ (NodeStatus::RUNNING, action_3.status ());
107
+ ASSERT_EQ (NodeStatus::RUNNING, state);
108
+
109
+ std::this_thread::sleep_for (milliseconds (110 ));
110
+
111
+ ASSERT_EQ (NodeStatus::IDLE, action_1.status ());
112
+ ASSERT_EQ (NodeStatus::IDLE, action_2.status ());
113
+ ASSERT_EQ (NodeStatus::SUCCESS, action_3.status ());
114
+ ASSERT_EQ (NodeStatus::SUCCESS, state);
115
+ }
116
+
117
+ TEST_F (SwitchTest, CaseSwitchToDefault)
118
+ {
119
+ bb->set (" variable" , " 1" );
120
+ BT::NodeStatus state = root->executeTick ();
121
+
122
+ ASSERT_EQ (NodeStatus::RUNNING, action_1.status ());
123
+ ASSERT_EQ (NodeStatus::IDLE, action_2.status ());
124
+ ASSERT_EQ (NodeStatus::IDLE, action_3.status ());
125
+ ASSERT_EQ (NodeStatus::RUNNING, state);
126
+
127
+ std::this_thread::sleep_for (milliseconds (10 ));
128
+ state = root->executeTick ();
129
+ ASSERT_EQ (NodeStatus::RUNNING, action_1.status ());
130
+ ASSERT_EQ (NodeStatus::IDLE, action_2.status ());
131
+ ASSERT_EQ (NodeStatus::IDLE, action_3.status ());
132
+ ASSERT_EQ (NodeStatus::RUNNING, state);
133
+
134
+ // Switch Node feels changes only when tick ? (no while loop inside,
135
+ // not reactive)
136
+ std::this_thread::sleep_for (milliseconds (10 ));
137
+ bb->set (" variable" , " " );
138
+ std::this_thread::sleep_for (milliseconds (10 ));
139
+ ASSERT_EQ (NodeStatus::RUNNING, action_1.status ());
140
+ ASSERT_EQ (NodeStatus::IDLE, action_2.status ());
141
+ ASSERT_EQ (NodeStatus::IDLE, action_3.status ());
142
+ ASSERT_EQ (NodeStatus::RUNNING, root->status ());
143
+
144
+ std::this_thread::sleep_for (milliseconds (10 ));
145
+ state = root->executeTick ();
146
+ ASSERT_EQ (NodeStatus::IDLE, action_1.status ());
147
+ ASSERT_EQ (NodeStatus::IDLE, action_2.status ());
148
+ ASSERT_EQ (NodeStatus::RUNNING, action_3.status ());
149
+ ASSERT_EQ (NodeStatus::RUNNING, state);
150
+
151
+ std::this_thread::sleep_for (milliseconds (110 ));
152
+
153
+ ASSERT_EQ (NodeStatus::IDLE, action_1.status ());
154
+ ASSERT_EQ (NodeStatus::IDLE, action_2.status ());
155
+ ASSERT_EQ (NodeStatus::SUCCESS, action_3.status ());
156
+ ASSERT_EQ (NodeStatus::SUCCESS, root->status ());
157
+ }
158
+
159
+ TEST_F (SwitchTest, CaseSwitchToAction2)
160
+ {
161
+ bb->set (" variable" , " 1" );
162
+ BT::NodeStatus state = root->executeTick ();
163
+
164
+ ASSERT_EQ (NodeStatus::RUNNING, action_1.status ());
165
+ ASSERT_EQ (NodeStatus::IDLE, action_2.status ());
166
+ ASSERT_EQ (NodeStatus::IDLE, action_3.status ());
167
+ ASSERT_EQ (NodeStatus::RUNNING, state);
168
+
169
+ bb->set (" variable" , " 2" );
170
+ std::this_thread::sleep_for (milliseconds (10 ));
171
+ state = root->executeTick ();
172
+ ASSERT_EQ (NodeStatus::IDLE, action_1.status ());
173
+ ASSERT_EQ (NodeStatus::RUNNING, action_2.status ());
174
+ ASSERT_EQ (NodeStatus::IDLE, action_3.status ());
175
+ ASSERT_EQ (NodeStatus::RUNNING, state);
176
+
177
+ std::this_thread::sleep_for (milliseconds (110 ));
178
+
179
+ ASSERT_EQ (NodeStatus::IDLE, action_1.status ());
180
+ ASSERT_EQ (NodeStatus::SUCCESS, action_2.status ());
181
+ ASSERT_EQ (NodeStatus::IDLE, action_3.status ());
182
+ ASSERT_EQ (NodeStatus::SUCCESS, root->status ());
183
+ }
184
+
185
+ TEST_F (SwitchTest, ActionFailure)
186
+ {
187
+ bb->set (" variable" , " 1" );
188
+ BT::NodeStatus state = root->executeTick ();
189
+
190
+ ASSERT_EQ (NodeStatus::RUNNING, action_1.status ());
191
+ ASSERT_EQ (NodeStatus::IDLE, action_2.status ());
192
+ ASSERT_EQ (NodeStatus::IDLE, action_3.status ());
193
+ ASSERT_EQ (NodeStatus::RUNNING, state);
194
+
195
+ // Switch Node does not halt after failure ?
196
+ std::this_thread::sleep_for (milliseconds (10 ));
197
+ action_1.setStatus (NodeStatus::FAILURE);
198
+ state = root->executeTick ();
199
+ ASSERT_EQ (NodeStatus::FAILURE, action_1.status ());
200
+ ASSERT_EQ (NodeStatus::IDLE, action_2.status ());
201
+ ASSERT_EQ (NodeStatus::IDLE, action_3.status ());
202
+ ASSERT_EQ (NodeStatus::FAILURE, state);
203
+
204
+ state = root->executeTick ();
205
+ state = root->executeTick ();
206
+ ASSERT_EQ (NodeStatus::FAILURE, action_1.status ());
207
+ ASSERT_EQ (NodeStatus::IDLE, action_2.status ());
208
+ ASSERT_EQ (NodeStatus::IDLE, action_3.status ());
209
+ ASSERT_EQ (NodeStatus::FAILURE, state);
210
+ }
0 commit comments