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 
20 struct SimpleParallelTest : testing::Test
21 {
25 
28 
30  : root("root_parallel", 4)
31  , action_1("action_1")
32  , condition_1("condition_1")
33  , action_2("action_2")
34  , condition_2("condition_2")
35  {
36  root.addChild(&condition_1);
37  root.addChild(&action_1);
38  root.addChild(&condition_2);
39  root.addChild(&action_2);
40  }
42  {
43  haltAllActions(&root);
44  }
45 };
46 
47 struct ComplexParallelTest : testing::Test
48 {
52 
55 
58 
61 
63  : root("root", 2)
64  , parallel_1("par1", 3)
65  , parallel_2("par2", 1)
66  , action_1("action_1")
67  , condition_1("condition_1")
68  , action_2("action_2")
69  , condition_2("condition_2")
70  , action_3("action_3")
71  , condition_3("condition_3")
72  {
73  root.addChild(&parallel_1);
74  {
75  parallel_1.addChild(&condition_1);
76  parallel_1.addChild(&action_1);
77  parallel_1.addChild(&condition_2);
78  parallel_1.addChild(&action_2);
79  }
80  root.addChild(&parallel_2);
81  {
82  parallel_2.addChild(&condition_3);
83  parallel_2.addChild(&action_3);
84  }
85  }
87  {
88  haltAllActions(&root);
89  }
90 };
91 
92 /****************TESTS START HERE***************************/
93 
94 TEST_F(SimpleParallelTest, ConditionsTrue)
95 {
97 
98  ASSERT_EQ(NodeStatus::IDLE, condition_1.status());
99  ASSERT_EQ(NodeStatus::IDLE, condition_2.status());
100  ASSERT_EQ(NodeStatus::RUNNING, action_1.status());
101  ASSERT_EQ(NodeStatus::RUNNING, action_2.status());
102  ASSERT_EQ(NodeStatus::RUNNING, state);
103 }
104 
106 {
107  root.setThresholdM(3);
108  action_2.setTime(200);
109  root.executeTick();
110  std::this_thread::sleep_for(std::chrono::milliseconds(500));
111  BT::NodeStatus state = root.executeTick();
112 
113  ASSERT_EQ(NodeStatus::IDLE, condition_1.status());
114  ASSERT_EQ(NodeStatus::IDLE, condition_2.status());
115  ASSERT_EQ(NodeStatus::IDLE, action_1.status());
116  ASSERT_EQ(NodeStatus::IDLE, action_2.status());
117  ASSERT_EQ(NodeStatus::SUCCESS, state);
118 }
119 
121 {
122  root.setThresholdM(1);
123  BT::NodeStatus state = root.executeTick();
124 
125  ASSERT_EQ(NodeStatus::IDLE, condition_1.status());
126  ASSERT_EQ(NodeStatus::IDLE, condition_2.status());
127  ASSERT_EQ(NodeStatus::IDLE, action_1.status());
128  ASSERT_EQ(NodeStatus::IDLE, action_2.status());
129  ASSERT_EQ(NodeStatus::SUCCESS, state);
130 }
131 TEST_F(ComplexParallelTest, ConditionsTrue)
132 {
133  BT::NodeStatus state = root.executeTick();
134 
135  ASSERT_EQ(NodeStatus::IDLE, condition_1.status());
136  ASSERT_EQ(NodeStatus::IDLE, condition_2.status());
137  ASSERT_EQ(NodeStatus::IDLE, condition_3.status());
138  ASSERT_EQ(NodeStatus::RUNNING, action_1.status());
139  ASSERT_EQ(NodeStatus::RUNNING, action_2.status());
140  ASSERT_EQ(NodeStatus::IDLE, action_3.status());
141  ASSERT_EQ(NodeStatus::RUNNING, parallel_1.status());
142  ASSERT_EQ(NodeStatus::IDLE, parallel_2.status());
143  ASSERT_EQ(NodeStatus::RUNNING, state);
144 }
145 
146 TEST_F(ComplexParallelTest, Condition3False)
147 {
148  condition_3.setBoolean(false);
149  BT::NodeStatus state = root.executeTick();
150 
151  ASSERT_EQ(NodeStatus::IDLE, condition_1.status());
152  ASSERT_EQ(NodeStatus::IDLE, condition_2.status());
153  ASSERT_EQ(NodeStatus::IDLE, condition_3.status());
154  ASSERT_EQ(NodeStatus::RUNNING, action_1.status());
155  ASSERT_EQ(NodeStatus::RUNNING, action_2.status());
156  ASSERT_EQ(NodeStatus::RUNNING, action_3.status());
157  ASSERT_EQ(NodeStatus::RUNNING, parallel_1.status());
158  ASSERT_EQ(NodeStatus::RUNNING, parallel_2.status());
159  ASSERT_EQ(NodeStatus::RUNNING, state);
160 }
161 
162 TEST_F(ComplexParallelTest, Condition3FalseAction1Done)
163 {
164  action_2.setTime(10);
165  action_3.setTime(10);
166 
167  condition_3.setBoolean(false);
168  BT::NodeStatus state = root.executeTick();
169  std::this_thread::sleep_for(std::chrono::milliseconds(500));
170 
171  ASSERT_EQ(NodeStatus::IDLE, condition_1.status());
172  ASSERT_EQ(NodeStatus::IDLE, condition_2.status());
173  ASSERT_EQ(NodeStatus::IDLE, condition_3.status());
174  ASSERT_EQ(NodeStatus::SUCCESS,
175  action_1.status()); // success not read yet by the node parallel_1
176  ASSERT_EQ(NodeStatus::RUNNING,
177  parallel_1.status()); // parallel_1 hasn't realize (yet) that action_1 has succeeded
178 
179  state = root.executeTick();
180 
181  ASSERT_EQ(NodeStatus::IDLE, action_1.status());
182  ASSERT_EQ(NodeStatus::IDLE, parallel_1.status());
183  ASSERT_EQ(NodeStatus::IDLE, action_2.status());
184  ASSERT_EQ(NodeStatus::RUNNING, action_3.status());
185  ASSERT_EQ(NodeStatus::RUNNING, parallel_2.status());
186  ASSERT_EQ(NodeStatus::RUNNING, state);
187 
188  state = root.executeTick();
189  std::this_thread::sleep_for(std::chrono::milliseconds(1500));
190  state = root.executeTick();
191 
192  ASSERT_EQ(NodeStatus::IDLE, parallel_2.status());
193  ASSERT_EQ(NodeStatus::IDLE, action_1.status());
194  ASSERT_EQ(NodeStatus::IDLE, parallel_1.status());
195  ASSERT_EQ(NodeStatus::IDLE, action_3.status());
196  ASSERT_EQ(NodeStatus::IDLE, parallel_2.status());
197  ASSERT_EQ(NodeStatus::SUCCESS, state);
198 }
BT::ParallelNode parallel_2
BT::ConditionTestNode condition_2
BT::ParallelNode root
BT::AsyncActionTest action_1
void haltAllActions(TreeNode *root_node)
BT::AsyncActionTest action_2
BT::AsyncActionTest action_3
void setThresholdM(unsigned int threshold_M)
BT::ParallelNode parallel_1
void addChild(TreeNode *child)
BT::AsyncActionTest action_1
BT::ParallelNode root
NodeStatus status() const
Definition: tree_node.cpp:75
void setTime(int time)
TEST_F(SimpleParallelTest, ConditionsTrue)
NodeStatus
Definition: basic_types.h:28
virtual BT::NodeStatus executeTick()
The method that will be executed to invoke tick(); and setStatus();.
Definition: tree_node.cpp:35
BT::ConditionTestNode condition_2
BT::ConditionTestNode condition_1
BT::ConditionTestNode condition_1
BT::AsyncActionTest action_2
BT::ConditionTestNode condition_3


behaviortree_cpp
Author(s): Michele Colledanchise, Davide Faconti
autogenerated on Sat Feb 2 2019 04:01:53