gtest_parallel.cpp
Go to the documentation of this file.
1 /* Copyright (C) 2015-2017 Michele Colledanchise - All Rights Reserved
2 *
3 * Permission is hereby granted, free of charge, to any person obtaining a copy of this software and associated documentation files (the "Software"),
4 * to deal in the Software without restriction, including without limitation the rights to use, copy, modify, merge, publish, distribute, sublicense,
5 * 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:
6 * The above copyright notice and this permission notice shall be included in all copies or substantial portions of the Software.
7 *
8 * THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY,
9 * 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,
10 * 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.
11 */
12 
13 #include <gtest/gtest.h>
14 #include "action_test_node.h"
15 #include "condition_test_node.h"
17 
18 using BT::NodeStatus;
19 using std::chrono::milliseconds;
20 
21 struct SimpleParallelTest : testing::Test
22 {
26 
29 
31  : root("root_parallel", 4)
32  , action_1("action_1", milliseconds(100) )
33  , condition_1("condition_1")
34  , action_2("action_2", milliseconds(300))
35  , condition_2("condition_2")
36  {
37  root.addChild(&condition_1);
38  root.addChild(&action_1);
39  root.addChild(&condition_2);
40  root.addChild(&action_2);
41  }
43  {
44  haltAllActions(&root);
45  }
46 };
47 
48 struct ComplexParallelTest : testing::Test
49 {
53 
56 
59 
62 
64  : parallel_root("root", 2)
65  , parallel_left("par1", 3)
66  , parallel_right("par2", 1)
67  , action_L1("action_1", milliseconds(100) )
68  , condition_L1("condition_1")
69  , action_L2("action_2", milliseconds(200) )
70  , condition_L2("condition_2")
71  , action_R("action_3", milliseconds(400) )
72  , condition_R("condition_3")
73  {
74  parallel_root.addChild(&parallel_left);
75  {
76  parallel_left.addChild(&condition_L1);
77  parallel_left.addChild(&action_L1);
78  parallel_left.addChild(&condition_L2);
79  parallel_left.addChild(&action_L2);
80  }
81  parallel_root.addChild(&parallel_right);
82  {
83  parallel_right.addChild(&condition_R);
84  parallel_right.addChild(&action_R);
85  }
86  }
88  {
89  haltAllActions(&parallel_root);
90  }
91 };
92 
93 /****************TESTS START HERE***************************/
94 
95 TEST_F(SimpleParallelTest, ConditionsTrue)
96 {
98 
99  ASSERT_EQ(NodeStatus::SUCCESS, condition_1.status());
100  ASSERT_EQ(NodeStatus::SUCCESS, condition_2.status());
101  ASSERT_EQ(NodeStatus::RUNNING, action_1.status());
102  ASSERT_EQ(NodeStatus::RUNNING, action_2.status());
103  ASSERT_EQ(NodeStatus::RUNNING, state);
104 
105  std::this_thread::sleep_for( milliseconds(200) );
106  state = root.executeTick();
107 
108  ASSERT_EQ(NodeStatus::SUCCESS, condition_1.status());
109  ASSERT_EQ(NodeStatus::SUCCESS, condition_2.status());
110  ASSERT_EQ(NodeStatus::SUCCESS, action_1.status());
111  ASSERT_EQ(NodeStatus::RUNNING, action_2.status());
112  ASSERT_EQ(NodeStatus::RUNNING, state);
113 
114  std::this_thread::sleep_for( milliseconds(200) );
115  state = root.executeTick();
116 
117  ASSERT_EQ(NodeStatus::IDLE, condition_1.status());
118  ASSERT_EQ(NodeStatus::IDLE, condition_2.status());
119  ASSERT_EQ(NodeStatus::IDLE, action_1.status());
120  ASSERT_EQ(NodeStatus::IDLE, action_2.status());
121  ASSERT_EQ(NodeStatus::SUCCESS, state);
122 }
123 
125 {
126  root.setThresholdM(3);
127  action_1.setTime( milliseconds(100) );
128  action_2.setTime( milliseconds(500) ); // this takes a lot of time
129 
130  BT::NodeStatus state = root.executeTick();
131  // first tick, zero wait
132  ASSERT_EQ(NodeStatus::SUCCESS, condition_1.status());
133  ASSERT_EQ(NodeStatus::SUCCESS, condition_2.status());
134  ASSERT_EQ(NodeStatus::RUNNING, action_1.status());
135  ASSERT_EQ(NodeStatus::RUNNING, action_2.status());
136  ASSERT_EQ(NodeStatus::RUNNING, state);
137 
138  std::this_thread::sleep_for( milliseconds(150) );
139  state = root.executeTick();
140  // second tick: action1 should be completed, but not action2
141  // nevertheless it is sufficient because threshold is 3
142  ASSERT_EQ(NodeStatus::IDLE, condition_1.status());
143  ASSERT_EQ(NodeStatus::IDLE, condition_2.status());
144  ASSERT_EQ(NodeStatus::IDLE, action_1.status());
145  ASSERT_EQ(NodeStatus::IDLE, action_2.status());
146  ASSERT_EQ(NodeStatus::SUCCESS, state);
147 }
148 
150 {
151  root.setThresholdM(2);
152  BT::NodeStatus state = root.executeTick();
153 
154  ASSERT_EQ(NodeStatus::IDLE, condition_1.status());
155  ASSERT_EQ(NodeStatus::IDLE, condition_2.status());
156  ASSERT_EQ(NodeStatus::IDLE, action_1.status());
157  ASSERT_EQ(NodeStatus::IDLE, action_2.status());
158  ASSERT_EQ(NodeStatus::SUCCESS, state);
159 }
160 
161 TEST_F(ComplexParallelTest, ConditionsTrue)
162 {
163  BT::NodeStatus state = parallel_root.executeTick();
164 
165  ASSERT_EQ(NodeStatus::RUNNING, parallel_left.status());
166  ASSERT_EQ(NodeStatus::SUCCESS, condition_L1.status());
167  ASSERT_EQ(NodeStatus::SUCCESS, condition_L2.status());
168  ASSERT_EQ(NodeStatus::RUNNING, action_L1.status());
169  ASSERT_EQ(NodeStatus::RUNNING, action_L2.status());
170 
171  ASSERT_EQ(NodeStatus::SUCCESS, parallel_right.status());
172  ASSERT_EQ(NodeStatus::IDLE, condition_R.status());
173  ASSERT_EQ(NodeStatus::IDLE, action_R.status());
174 
175  ASSERT_EQ(NodeStatus::RUNNING, state);
176  //----------------------------------------
177  std::this_thread::sleep_for(milliseconds(200));
178  state = parallel_root.executeTick();
179 
180  ASSERT_EQ(NodeStatus::IDLE, parallel_left.status());
181  ASSERT_EQ(NodeStatus::IDLE, condition_L1.status());
182  ASSERT_EQ(NodeStatus::IDLE, condition_L2.status());
183  ASSERT_EQ(NodeStatus::IDLE, action_L1.status());
184  ASSERT_EQ(NodeStatus::IDLE, action_L2.status());
185 
186  ASSERT_EQ(NodeStatus::IDLE, parallel_right.status());
187  ASSERT_EQ(NodeStatus::IDLE, condition_R.status());
188  ASSERT_EQ(NodeStatus::IDLE, action_R.status());
189 
190  ASSERT_EQ(NodeStatus::SUCCESS, state);
191 }
192 
193 TEST_F(ComplexParallelTest, ConditionRightFalse)
194 {
195  condition_R.setBoolean(false);
196  BT::NodeStatus state = parallel_root.executeTick();
197 
198  // All the actions are running
199 
200  ASSERT_EQ(NodeStatus::RUNNING, parallel_left.status());
201  ASSERT_EQ(NodeStatus::SUCCESS, condition_L1.status());
202  ASSERT_EQ(NodeStatus::SUCCESS, condition_L2.status());
203  ASSERT_EQ(NodeStatus::RUNNING, action_L1.status());
204  ASSERT_EQ(NodeStatus::RUNNING, action_L2.status());
205 
206  ASSERT_EQ(NodeStatus::RUNNING, parallel_right.status());
207  ASSERT_EQ(NodeStatus::FAILURE, condition_R.status());
208  ASSERT_EQ(NodeStatus::RUNNING, action_R.status());
209 
210  ASSERT_EQ(NodeStatus::RUNNING, state);
211 
212  //----------------------------------------
213  std::this_thread::sleep_for(milliseconds(500));
214  state = parallel_root.executeTick();
215 
216  ASSERT_EQ(NodeStatus::IDLE, parallel_left.status());
217  ASSERT_EQ(NodeStatus::IDLE, condition_L1.status());
218  ASSERT_EQ(NodeStatus::IDLE, condition_L2.status());
219  ASSERT_EQ(NodeStatus::IDLE, action_L1.status());
220  ASSERT_EQ(NodeStatus::IDLE, action_L2.status());
221 
222  ASSERT_EQ(NodeStatus::IDLE, parallel_right.status());
223  ASSERT_EQ(NodeStatus::IDLE, condition_R.status());
224  ASSERT_EQ(NodeStatus::IDLE, action_R.status());
225 
226  ASSERT_EQ(NodeStatus::SUCCESS, state);
227 }
228 
229 TEST_F(ComplexParallelTest, ConditionRightFalseAction1Done)
230 {
231  condition_R.setBoolean(false);
232 
233  parallel_left.setThresholdM(4);
234 
235  BT::NodeStatus state = parallel_root.executeTick();
236  std::this_thread::sleep_for(milliseconds(300));
237 
238  // parallel_1 hasn't realize (yet) that action_1 has succeeded
239  ASSERT_EQ(NodeStatus::RUNNING, parallel_left.status());
240  ASSERT_EQ(NodeStatus::SUCCESS, condition_L1.status());
241  ASSERT_EQ(NodeStatus::SUCCESS, condition_L2.status());
242  ASSERT_EQ(NodeStatus::SUCCESS, action_L1.status());
243  ASSERT_EQ(NodeStatus::SUCCESS, action_L2.status());
244 
245  ASSERT_EQ(NodeStatus::RUNNING, parallel_right.status());
246 
247  //------------------------
248  state = parallel_root.executeTick();
249 
250  ASSERT_EQ(NodeStatus::SUCCESS, parallel_left.status());
251  ASSERT_EQ(NodeStatus::IDLE, condition_L1.status());
252  ASSERT_EQ(NodeStatus::IDLE, condition_L2.status());
253  ASSERT_EQ(NodeStatus::IDLE, action_L1.status());
254  ASSERT_EQ(NodeStatus::IDLE, action_L2.status());
255 
256  ASSERT_EQ(NodeStatus::RUNNING, parallel_right.status());
257  ASSERT_EQ(NodeStatus::RUNNING, action_R.status());
258 
259  ASSERT_EQ(NodeStatus::RUNNING, state);
260 
261  //----------------------------------
262  std::this_thread::sleep_for(milliseconds(300));
263  state = parallel_root.executeTick();
264 
265  ASSERT_EQ(NodeStatus::IDLE, parallel_left.status());
266  ASSERT_EQ(NodeStatus::IDLE, action_L1.status());
267 
268  ASSERT_EQ(NodeStatus::IDLE, parallel_right.status());
269  ASSERT_EQ(NodeStatus::IDLE, action_R.status());
270 
271  ASSERT_EQ(NodeStatus::SUCCESS, state);
272 }
BT::AsyncActionTest action_L2
BT::ConditionTestNode condition_L2
BT::ConditionTestNode condition_2
BT::ConditionTestNode condition_R
BT::AsyncActionTest action_L1
void haltAllActions(TreeNode *root_node)
BT::ParallelNode parallel_right
void setThresholdM(unsigned int threshold_M)
BT::ParallelNode parallel_left
BT::AsyncActionTest action_R
void setTime(BT::Duration time)
BT::ConditionTestNode condition_L1
void addChild(TreeNode *child)
The method used to add nodes to the children vector.
BT::AsyncActionTest action_1
BT::ParallelNode root
BT::ParallelNode parallel_root
NodeStatus status() const
Definition: tree_node.cpp:56
TEST_F(SimpleParallelTest, ConditionsTrue)
NodeStatus
Definition: basic_types.h:35
virtual BT::NodeStatus executeTick()
The method that should be used to invoke tick() and setStatus();.
Definition: tree_node.cpp:33
BT::ConditionTestNode condition_1
BT::AsyncActionTest action_2


behaviortree_cpp
Author(s): Michele Colledanchise, Davide Faconti
autogenerated on Sat Jun 8 2019 18:04:05