PX4 Firmware
PX4 Autopilot Software http://px4.io
HysteresisTest.cpp
Go to the documentation of this file.
1 /****************************************************************************
2  *
3  * Copyright (C) 2012-2019 PX4 Development Team. All rights reserved.
4  *
5  * Redistribution and use in source and binary forms, with or without
6  * modification, are permitted provided that the following conditions
7  * are met:
8  *
9  * 1. Redistributions of source code must retain the above copyright
10  * notice, this list of conditions and the following disclaimer.
11  * 2. Redistributions in binary form must reproduce the above copyright
12  * notice, this list of conditions and the following disclaimer in
13  * the documentation and/or other materials provided with the
14  * distribution.
15  * 3. Neither the name PX4 nor the names of its contributors may be
16  * used to endorse or promote products derived from this software
17  * without specific prior written permission.
18  *
19  * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
20  * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
21  * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
22  * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
23  * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
24  * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
25  * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
26  * OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
27  * AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
28  * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
29  * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
30  * POSSIBILITY OF SUCH DAMAGE.
31  *
32  ****************************************************************************/
33 
34 /**
35  * @file hysteresis_test.cpp
36  * Tests for system timing hysteresis.
37  */
38 
39 #include <gtest/gtest.h>
40 
41 #include "hysteresis.h"
42 
43 
44 static constexpr hrt_abstime SOME_START_TIME = 1558359616134000llu;
45 
46 
47 TEST(Hysteresis, InitFalse)
48 {
49  systemlib::Hysteresis hysteresis(false);
50  EXPECT_FALSE(hysteresis.get_state());
51 }
52 
53 TEST(Hysteresis, InitTrue)
54 {
55  systemlib::Hysteresis hysteresis(true);
56  EXPECT_TRUE(hysteresis.get_state());
57 }
58 
59 TEST(Hysteresis, Zero)
60 {
61  hrt_abstime time_us = SOME_START_TIME;
62 
63  // Default is 0 hysteresis.
64  systemlib::Hysteresis hysteresis(false);
65  EXPECT_FALSE(hysteresis.get_state());
66 
67  // Change and see result immediately.
68  hysteresis.set_state_and_update(true, time_us);
69  EXPECT_TRUE(hysteresis.get_state());
70  hysteresis.set_state_and_update(false, time_us);
71  EXPECT_FALSE(hysteresis.get_state());
72  hysteresis.set_state_and_update(true, time_us);
73  EXPECT_TRUE(hysteresis.get_state());
74 
75  time_us += 1000;
76  // A wait won't change anything.
77  hysteresis.update(time_us);
78  EXPECT_TRUE(hysteresis.get_state());
79 }
80 
81 TEST(Hysteresis, ChangeAfterTime)
82 {
83  hrt_abstime time_us = SOME_START_TIME;
84 
85  systemlib::Hysteresis hysteresis(false);
86  hysteresis.set_hysteresis_time_from(false, 5000);
87  hysteresis.set_hysteresis_time_from(true, 3000);
88 
89  // Change to true.
90  hysteresis.set_state_and_update(true, time_us);
91  EXPECT_FALSE(hysteresis.get_state());
92  time_us += 4000;
93  hysteresis.update(time_us);
94  EXPECT_FALSE(hysteresis.get_state());
95  time_us += 2000;
96  hysteresis.update(time_us);
97  EXPECT_TRUE(hysteresis.get_state());
98 
99  // Change back to false.
100  hysteresis.set_state_and_update(false, time_us);
101  EXPECT_TRUE(hysteresis.get_state());
102  time_us += 1000;
103  hysteresis.update(time_us);
104  EXPECT_TRUE(hysteresis.get_state());
105  time_us += 3000;
106  hysteresis.update(time_us);
107  EXPECT_FALSE(hysteresis.get_state());
108 }
109 
110 TEST(Hysteresis, HysteresisChanged)
111 {
112  hrt_abstime time_us = SOME_START_TIME;
113 
114  systemlib::Hysteresis hysteresis(false);
115  hysteresis.set_hysteresis_time_from(true, 2000);
116  hysteresis.set_hysteresis_time_from(false, 5000);
117 
118  // Change to true.
119  hysteresis.set_state_and_update(true, time_us);
120  EXPECT_FALSE(hysteresis.get_state());
121  time_us += 3000;
122  hysteresis.update(time_us);
123  EXPECT_FALSE(hysteresis.get_state());
124  time_us += 3000;
125  hysteresis.update(time_us);
126  EXPECT_TRUE(hysteresis.get_state());
127 
128  // Change hysteresis time.
129  hysteresis.set_hysteresis_time_from(true, 10000);
130 
131  // Change back to false.
132  hysteresis.set_state_and_update(false, time_us);
133  EXPECT_TRUE(hysteresis.get_state());
134  time_us += 7000;
135  hysteresis.update(time_us);
136  EXPECT_TRUE(hysteresis.get_state());
137  time_us += 5000;
138  hysteresis.update(time_us);
139  EXPECT_FALSE(hysteresis.get_state());
140 }
141 
142 TEST(Hysteresis, ChangeAfterMultipleSets)
143 {
144  hrt_abstime time_us = SOME_START_TIME;
145 
146  systemlib::Hysteresis hysteresis(false);
147  hysteresis.set_hysteresis_time_from(true, 5000);
148  hysteresis.set_hysteresis_time_from(false, 5000);
149 
150  // Change to true.
151  hysteresis.set_state_and_update(true, time_us);
152  EXPECT_FALSE(hysteresis.get_state());
153  time_us += 3000;
154  hysteresis.set_state_and_update(true, time_us);
155  EXPECT_FALSE(hysteresis.get_state());
156  time_us += 3000;
157  hysteresis.set_state_and_update(true, time_us);
158  EXPECT_TRUE(hysteresis.get_state());
159 
160  // Change to false.
161  hysteresis.set_state_and_update(false, time_us);
162  EXPECT_TRUE(hysteresis.get_state());
163  time_us += 3000;
164  hysteresis.set_state_and_update(false, time_us);
165  EXPECT_TRUE(hysteresis.get_state());
166  time_us += 3000;
167  hysteresis.set_state_and_update(false, time_us);
168  EXPECT_FALSE(hysteresis.get_state());
169 }
170 
171 TEST(Hysteresis, TakeChangeBack)
172 {
173  hrt_abstime time_us = SOME_START_TIME;
174 
175  systemlib::Hysteresis hysteresis(false);
176  hysteresis.set_hysteresis_time_from(false, 5000);
177 
178  // Change to true.
179  hysteresis.set_state_and_update(true, time_us);
180  EXPECT_FALSE(hysteresis.get_state());
181  time_us += 3000;
182  hysteresis.update(time_us);
183  EXPECT_FALSE(hysteresis.get_state());
184  // Change your mind to false.
185  hysteresis.set_state_and_update(false, time_us);
186  EXPECT_FALSE(hysteresis.get_state());
187  time_us += 6000;
188  hysteresis.update(time_us);
189  EXPECT_FALSE(hysteresis.get_state());
190 
191  // And true again
192  hysteresis.set_state_and_update(true, time_us);
193  EXPECT_FALSE(hysteresis.get_state());
194  time_us += 3000;
195  hysteresis.update(time_us);
196  EXPECT_FALSE(hysteresis.get_state());
197  time_us += 3000;
198  hysteresis.update(time_us);
199  EXPECT_TRUE(hysteresis.get_state());
200 
201  // The other directory is immediate.
202  hysteresis.set_state_and_update(false, time_us);
203  EXPECT_FALSE(hysteresis.get_state());
204 }
void set_state_and_update(const bool new_state, const hrt_abstime &now_us)
Definition: hysteresis.cpp:57
bool get_state() const
Definition: hysteresis.h:60
void update(const hrt_abstime &now_us)
Definition: hysteresis.cpp:73
__BEGIN_DECLS typedef uint64_t hrt_abstime
Absolute time, in microsecond units.
Definition: drv_hrt.h:58
TEST(Hysteresis, InitFalse)
Hysteresis of a boolean value.
void set_hysteresis_time_from(const bool from_state, const hrt_abstime new_hysteresis_time_us)
Definition: hysteresis.cpp:46
static constexpr hrt_abstime SOME_START_TIME