gtest_decorator.cpp
Go to the documentation of this file.
1 /* Copyright (C) 2018-2019 Davide Faconti, Eurecat - 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 DeadlineTest : testing::Test
22 {
25 
26  DeadlineTest() : root("deadline", 300)
27  , action("action", milliseconds(500) )
28  {
29  root.setChild(&action);
30  }
31  ~DeadlineTest() = default;
32 };
33 
34 struct RepeatTest : testing::Test
35 {
38 
39  RepeatTest() : root("repeat", 3), action("action")
40  {
41  root.setChild(&action);
42  }
43  ~RepeatTest() = default;
44 };
45 
46 struct RepeatTestAsync : testing::Test
47 {
50 
51  RepeatTestAsync() : root("repeat", 3), action("action", milliseconds(100))
52  {
53  root.setChild(&action);
54  }
55  ~RepeatTestAsync() = default;
56 };
57 
58 struct RetryTest : testing::Test
59 {
62 
63  RetryTest() : root("retry", 3), action("action")
64  {
65  root.setChild(&action);
66  }
67  ~RetryTest() = default;
68 };
69 
70 struct TimeoutAndRetry : testing::Test
71 {
75 
77  timeout_root("deadline", 9)
78  , retry("retry", 1000)
79  , action("action")
80  {
81  timeout_root.setChild(&retry);
82  retry.setChild(&action);
83  }
84 };
85 
86 /****************TESTS START HERE***************************/
87 
88 TEST_F(DeadlineTest, DeadlineTriggeredTest)
89 {
91  // deadline in 300 ms, action requires 500 ms
92 
93  ASSERT_EQ(NodeStatus::RUNNING, action.status());
94  ASSERT_EQ(NodeStatus::RUNNING, state);
95 
96  std::this_thread::sleep_for(std::chrono::milliseconds(400));
97  state = root.executeTick();
98  ASSERT_EQ(NodeStatus::FAILURE, state);
99  ASSERT_EQ(NodeStatus::IDLE, action.status());
100 }
101 
102 TEST_F(DeadlineTest, DeadlineNotTriggeredTest)
103 {
104  action.setTime( milliseconds(200) );
105  // deadline in 300 ms
106 
107  BT::NodeStatus state = root.executeTick();
108 
109  ASSERT_EQ(NodeStatus::RUNNING, action.status());
110  ASSERT_EQ(NodeStatus::RUNNING, state);
111 
112  std::this_thread::sleep_for(std::chrono::milliseconds(400));
113  state = root.executeTick();
114  ASSERT_EQ(NodeStatus::IDLE, action.status());
115  ASSERT_EQ(NodeStatus::SUCCESS, state);
116 }
117 
118 TEST_F(RetryTest, RetryTestA)
119 {
120  action.setExpectedResult(NodeStatus::FAILURE);
121 
122  root.executeTick();
123  ASSERT_EQ(NodeStatus::FAILURE, root.status());
124  ASSERT_EQ(3, action.tickCount() );
125 
126  action.setExpectedResult(NodeStatus::SUCCESS);
127  action.resetTicks();
128 
129  root.executeTick();
130  ASSERT_EQ(NodeStatus::SUCCESS, root.status());
131  ASSERT_EQ(1, action.tickCount() );
132 }
133 
134 
136 {
137  action.setExpectedResult(NodeStatus::SUCCESS);
138 
139  auto res = root.executeTick();
140 
141  while(res == NodeStatus::RUNNING){
142  std::this_thread::sleep_for(std::chrono::milliseconds(20));
143  res = root.executeTick();
144  }
145 
146  ASSERT_EQ(NodeStatus::SUCCESS, root.status());
147  ASSERT_EQ(3, action.successCount() );
148  ASSERT_EQ(0, action.failureCount() );
149 
150  //-------------------
151  action.setExpectedResult(NodeStatus::FAILURE);
153 
154  res = root.executeTick();
155  while(res == NodeStatus::RUNNING){
156  std::this_thread::sleep_for(std::chrono::milliseconds(20));
157  res = root.executeTick();
158  }
159 
160  ASSERT_EQ(NodeStatus::FAILURE, root.status());
161  ASSERT_EQ(0, action.successCount() );
162  ASSERT_EQ(1, action.failureCount() );
163 
164 }
165 
166 TEST_F(RepeatTest, RepeatTestA)
167 {
168  action.setExpectedResult(NodeStatus::FAILURE);
169 
170  root.executeTick();
171  ASSERT_EQ(NodeStatus::FAILURE, root.status());
172  ASSERT_EQ(1, action.tickCount() );
173 
174  //-------------------
175  action.resetTicks();
176  action.setExpectedResult(NodeStatus::SUCCESS);
177 
178  root.executeTick();
179  ASSERT_EQ(NodeStatus::SUCCESS, root.status());
180  ASSERT_EQ(3, action.tickCount() );
181 }
182 
183 // https://github.com/BehaviorTree/BehaviorTree.CPP/issues/57
185 {
186  action.setExpectedResult(NodeStatus::FAILURE);
187 
188  auto t1 = std::chrono::high_resolution_clock::now();
189 
190  while( std::chrono::high_resolution_clock::now() < t1 + std::chrono::seconds(2) )
191  {
192  ASSERT_NE( timeout_root.executeTick(), BT::NodeStatus::IDLE );
193  std::this_thread::sleep_for( std::chrono::microseconds(50) );
194  }
195 }
BT::TimeoutNode timeout_root
int successCount() const
BT::TimeoutNode root
The TimeoutNode will halt() a running child if the latter has been RUNNING for more than a give time...
Definition: timeout_node.h:24
BT::RepeatNode root
int failureCount() const
TEST_F(DeadlineTest, DeadlineTriggeredTest)
The RepeatNode is used to execute a child several times, as long as it succeed.
Definition: repeat_node.h:36
BT::SyncActionTest action
~DeadlineTest()=default
The RetryNode is used to execute a child several times if it fails.
Definition: retry_node.h:36
BT::SyncActionTest action
void setChild(TreeNode *child)
BT::SyncActionTest action
NodeStatus executeTick() override
The method that should be used to invoke tick() and setStatus();.
BT::AsyncActionTest action
BT::RetryNode retry
void setTime(BT::Duration time)
BT::AsyncActionTest action
NodeStatus status() const
Definition: tree_node.cpp:56
NodeStatus
Definition: basic_types.h:35
void setExpectedResult(NodeStatus res)
int tickCount() const
BT::RepeatNode root
BT::RetryNode root


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