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  }
32  {
33  haltAllActions(&root);
34  }
35 };
36 
37 struct RepeatTest : testing::Test
38 {
41 
42  RepeatTest() : root("repeat", 3), action("action")
43  {
44  root.setChild(&action);
45  }
47  {
48  haltAllActions(&root);
49  }
50 };
51 
52 struct RetryTest : testing::Test
53 {
56 
57  RetryTest() : root("retry", 3), action("action")
58  {
59  root.setChild(&action);
60  }
62  {
63  haltAllActions(&root);
64  }
65 };
66 
67 struct TimeoutAndRetry : testing::Test
68 {
72 
74  timeout_root("deadline", 9)
75  , retry("retry", 1000)
76  , action("action")
77  {
78  timeout_root.setChild(&retry);
79  retry.setChild(&action);
80  }
82  {
83  haltAllActions(&timeout_root);
84  }
85 };
86 
87 /****************TESTS START HERE***************************/
88 
89 TEST_F(DeadlineTest, DeadlineTriggeredTest)
90 {
92  // deadline in 300 ms, action requires 500 ms
93 
94  ASSERT_EQ(NodeStatus::RUNNING, action.status());
95  ASSERT_EQ(NodeStatus::RUNNING, state);
96 
97  std::this_thread::sleep_for(std::chrono::milliseconds(400));
98  state = root.executeTick();
99  ASSERT_EQ(NodeStatus::FAILURE, state);
100  ASSERT_EQ(NodeStatus::IDLE, action.status());
101 }
102 
103 TEST_F(DeadlineTest, DeadlineNotTriggeredTest)
104 {
105  action.setTime( milliseconds(200) );
106  // deadline in 300 ms
107 
108  BT::NodeStatus state = root.executeTick();
109 
110  ASSERT_EQ(NodeStatus::RUNNING, action.status());
111  ASSERT_EQ(NodeStatus::RUNNING, state);
112 
113  std::this_thread::sleep_for(std::chrono::milliseconds(400));
114  state = root.executeTick();
115  ASSERT_EQ(NodeStatus::IDLE, action.status());
116  ASSERT_EQ(NodeStatus::SUCCESS, state);
117 }
118 
119 TEST_F(RetryTest, RetryTestA)
120 {
121  action.setBoolean(false);
122 
123  root.executeTick();
124  ASSERT_EQ(NodeStatus::FAILURE, root.status());
125  ASSERT_EQ(3, action.tickCount() );
126 
127  action.setBoolean(true);
128  action.resetTicks();
129 
130  root.executeTick();
131  ASSERT_EQ(NodeStatus::SUCCESS, root.status());
132  ASSERT_EQ(1, action.tickCount() );
133 }
134 
135 TEST_F(RepeatTest, RepeatTestA)
136 {
137  action.setBoolean(false);
138 
139  root.executeTick();
140  ASSERT_EQ(NodeStatus::FAILURE, root.status());
141  ASSERT_EQ(1, action.tickCount() );
142 
143  //-------------------
144  action.resetTicks();
145  action.setBoolean(true);
146 
147  root.executeTick();
148  ASSERT_EQ(NodeStatus::SUCCESS, root.status());
149  ASSERT_EQ(3, action.tickCount() );
150 }
151 
152 // https://github.com/BehaviorTree/BehaviorTree.CPP/issues/57
154 {
155  action.setBoolean( false );
156 
157  auto t1 = std::chrono::high_resolution_clock::now();
158 
159  while( std::chrono::high_resolution_clock::now() < t1 + std::chrono::seconds(2) )
160  {
161  ASSERT_NE( timeout_root.executeTick(), BT::NodeStatus::IDLE );
162  std::this_thread::sleep_for( std::chrono::microseconds(50) );
163  }
164 }
BT::TimeoutNode timeout_root
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:23
BT::RepeatNode root
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
The RetryNode is used to execute a child several times if it fails.
Definition: retry_node.h:36
void haltAllActions(TreeNode *root_node)
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)
NodeStatus status() const
Definition: tree_node.cpp:56
void setBoolean(bool boolean_value)
NodeStatus
Definition: basic_types.h:35
int tickCount() const
BT::RetryNode root


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