gtest_decorator.cpp
Go to the documentation of this file.
1 /* Copyright (C) 2018 Davide Faconti - 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 DeadlineTest : testing::Test
21 {
24 
25  DeadlineTest() : root("deadline", 250), action("action")
26  {
27  root.setChild(&action);
28  }
30  {
31  haltAllActions(&root);
32  }
33 };
34 
35 struct RepeatTest : testing::Test
36 {
39 
40  RepeatTest() : root("repeat", 3), action("action")
41  {
42  root.setChild(&action);
43  }
45  {
46  haltAllActions(&root);
47  }
48 };
49 
50 struct RetryTest : testing::Test
51 {
54 
55  RetryTest() : root("retry", 3), action("action")
56  {
57  root.setChild(&action);
58  }
60  {
61  haltAllActions(&root);
62  }
63 };
64 
65 /****************TESTS START HERE***************************/
66 
67 TEST_F(DeadlineTest, DeadlineTriggeredTest)
68 {
70  // deadline in 250 ms
71  action.setTime(3);
72 
73  ASSERT_EQ(NodeStatus::RUNNING, action.status());
74  ASSERT_EQ(NodeStatus::RUNNING, state);
75 
76  std::this_thread::sleep_for(std::chrono::milliseconds(350));
77  state = root.executeTick();
78  ASSERT_EQ(NodeStatus::IDLE, action.status());
79  ASSERT_EQ(NodeStatus::FAILURE, state);
80 }
81 
82 TEST_F(DeadlineTest, DeadlineNotTriggeredTest)
83 {
85  // deadline in 250 ms
86  action.setTime(2);
87 
88  ASSERT_EQ(NodeStatus::RUNNING, action.status());
89  ASSERT_EQ(NodeStatus::RUNNING, state);
90 
91  std::this_thread::sleep_for(std::chrono::milliseconds(350));
92  state = root.executeTick();
93  ASSERT_EQ(NodeStatus::IDLE, action.status());
94  ASSERT_EQ(NodeStatus::SUCCESS, state);
95 }
96 
97 TEST_F(RetryTest, RetryTestA)
98 {
99  action.setBoolean(false);
100 
101  root.executeTick();
102  ASSERT_EQ(NodeStatus::RUNNING, root.status());
103  ASSERT_EQ(1, action.tickCount() );
104 
105  root.executeTick();
106  ASSERT_EQ(NodeStatus::RUNNING, root.status());
107  ASSERT_EQ(2, action.tickCount() );
108 
109  root.executeTick();
110  ASSERT_EQ(NodeStatus::FAILURE, root.status());
111  ASSERT_EQ(3, action.tickCount() );
112 
113  // try again
114  action.resetTicks();
115  root.executeTick();
116  ASSERT_EQ(NodeStatus::RUNNING, root.status());
117  ASSERT_EQ(1, action.tickCount() );
118 
119  action.setBoolean(true);
120 
121  root.executeTick();
122  ASSERT_EQ(NodeStatus::SUCCESS, root.status());
123  ASSERT_EQ(2, action.tickCount() );
124 }
125 
126 TEST_F(RepeatTest, RepeatTestA)
127 {
128  action.setBoolean(false);
129 
130  root.executeTick();
131  ASSERT_EQ(NodeStatus::FAILURE, root.status());
132  ASSERT_EQ(1, action.tickCount() );
133 
134  root.executeTick();
135  ASSERT_EQ(NodeStatus::FAILURE, root.status());
136  ASSERT_EQ(2, action.tickCount() );
137 
138  //-------------------
139  action.resetTicks();
140  action.setBoolean(true);
141 
142  root.executeTick();
143  ASSERT_EQ(NodeStatus::RUNNING, root.status());
144  ASSERT_EQ(1, action.tickCount() );
145 
146  root.executeTick();
147  ASSERT_EQ(NodeStatus::RUNNING, root.status());
148  ASSERT_EQ(2, action.tickCount() );
149 
150  root.executeTick();
151  ASSERT_EQ(NodeStatus::SUCCESS, root.status());
152  ASSERT_EQ(3, action.tickCount() );
153 
154  //-------------------
155  action.resetTicks();
156  action.setBoolean(true);
157 
158  root.executeTick();
159  ASSERT_EQ(NodeStatus::RUNNING, root.status());
160  ASSERT_EQ(1, action.tickCount() );
161 
162  root.executeTick();
163  ASSERT_EQ(NodeStatus::RUNNING, root.status());
164  ASSERT_EQ(2, action.tickCount() );
165 
166  action.setBoolean(false);
167  root.executeTick();
168  ASSERT_EQ(NodeStatus::FAILURE, root.status());
169  ASSERT_EQ(3, action.tickCount() );
170 
171 }
BT::TimeoutNode root
BT::RepeatNode root
TEST_F(DeadlineTest, DeadlineTriggeredTest)
void haltAllActions(TreeNode *root_node)
BT::SyncActionTest action
void setChild(TreeNode *child)
BT::SyncActionTest action
NodeStatus executeTick() override
The method that will be executed to invoke tick(); and setStatus();.
BT::AsyncActionTest action
NodeStatus status() const
Definition: tree_node.cpp:75
void setTime(int time)
void setBoolean(bool boolean_value)
NodeStatus
Definition: basic_types.h:28
int tickCount() const
BT::RetryNode root


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