From e24d18f810ee85b7950c271a1c03bb1db16f9166 Mon Sep 17 00:00:00 2001 From: Lorenz Meier Date: Sun, 7 Aug 2016 11:25:26 +0200 Subject: [PATCH] Hysteresis test: Relax time for all tests for OS X CI system --- src/systemcmds/tests/test_hysteresis.cpp | 51 ++++++++++++------------ 1 file changed, 26 insertions(+), 25 deletions(-) diff --git a/src/systemcmds/tests/test_hysteresis.cpp b/src/systemcmds/tests/test_hysteresis.cpp index 6342b5869a..a0f4febe1f 100644 --- a/src/systemcmds/tests/test_hysteresis.cpp +++ b/src/systemcmds/tests/test_hysteresis.cpp @@ -15,6 +15,13 @@ private: bool _hysteresis_changed(); bool _change_after_multiple_sets(); bool _take_change_back(); + + // The CI system for Mac OS is not very fast +#ifdef __PX4_DARWIN + static const int f = 10; +#else + static const int f = 1; +#endif }; bool HysteresisTest::run_tests() @@ -61,7 +68,7 @@ bool HysteresisTest::_zero_case() ut_assert_true(hysteresis.get_state()); // A wait won't change anything. - usleep(1000); + usleep(1000 * f); hysteresis.update(); ut_assert_true(hysteresis.get_state()); @@ -70,12 +77,6 @@ bool HysteresisTest::_zero_case() bool HysteresisTest::_change_after_time() { - int f = 1; - - // The CI system for Mac OS is not very fast -#ifdef __PX4_DARWIN - f = 2; -#endif systemlib::Hysteresis hysteresis(false); hysteresis.set_hysteresis_time_from(false, 5000 * f); @@ -107,29 +108,29 @@ bool HysteresisTest::_change_after_time() bool HysteresisTest::_hysteresis_changed() { systemlib::Hysteresis hysteresis(false); - hysteresis.set_hysteresis_time_from(true, 2000); - hysteresis.set_hysteresis_time_from(false, 5000); + hysteresis.set_hysteresis_time_from(true, 2000 * f); + hysteresis.set_hysteresis_time_from(false, 5000 * f); // Change to true. hysteresis.set_state_and_update(true); ut_assert_false(hysteresis.get_state()); - usleep(3000); + usleep(3000 * f); hysteresis.update(); ut_assert_false(hysteresis.get_state()); - usleep(3000); + usleep(3000 * f); hysteresis.update(); ut_assert_true(hysteresis.get_state()); // Change hysteresis time. - hysteresis.set_hysteresis_time_from(true, 10000); + hysteresis.set_hysteresis_time_from(true, 10000 * f); // Change back to false. hysteresis.set_state_and_update(false); ut_assert_true(hysteresis.get_state()); - usleep(7000); + usleep(7000 * f); hysteresis.update(); ut_assert_true(hysteresis.get_state()); - usleep(5000); + usleep(5000 * f); hysteresis.update(); ut_assert_false(hysteresis.get_state()); @@ -139,26 +140,26 @@ bool HysteresisTest::_hysteresis_changed() bool HysteresisTest::_change_after_multiple_sets() { systemlib::Hysteresis hysteresis(false); - hysteresis.set_hysteresis_time_from(true, 5000); - hysteresis.set_hysteresis_time_from(false, 5000); + hysteresis.set_hysteresis_time_from(true, 5000 * f); + hysteresis.set_hysteresis_time_from(false, 5000 * f); // Change to true. hysteresis.set_state_and_update(true); ut_assert_false(hysteresis.get_state()); - usleep(3000); + usleep(3000 * f); hysteresis.set_state_and_update(true); ut_assert_false(hysteresis.get_state()); - usleep(3000); + usleep(3000 * f); hysteresis.set_state_and_update(true); ut_assert_true(hysteresis.get_state()); // Change to false. hysteresis.set_state_and_update(false); ut_assert_true(hysteresis.get_state()); - usleep(3000); + usleep(3000 * f); hysteresis.set_state_and_update(false); ut_assert_true(hysteresis.get_state()); - usleep(3000); + usleep(3000 * f); hysteresis.set_state_and_update(false); ut_assert_false(hysteresis.get_state()); @@ -168,28 +169,28 @@ bool HysteresisTest::_change_after_multiple_sets() bool HysteresisTest::_take_change_back() { systemlib::Hysteresis hysteresis(false); - hysteresis.set_hysteresis_time_from(false, 5000); + hysteresis.set_hysteresis_time_from(false, 5000 * f); // Change to true. hysteresis.set_state_and_update(true); ut_assert_false(hysteresis.get_state()); - usleep(3000); + usleep(3000 * f); hysteresis.update(); ut_assert_false(hysteresis.get_state()); // Change your mind to false. hysteresis.set_state_and_update(false); ut_assert_false(hysteresis.get_state()); - usleep(6000); + usleep(6000 * f); hysteresis.update(); ut_assert_false(hysteresis.get_state()); // And true again hysteresis.set_state_and_update(true); ut_assert_false(hysteresis.get_state()); - usleep(3000); + usleep(3000 * f); hysteresis.update(); ut_assert_false(hysteresis.get_state()); - usleep(3000); + usleep(3000 * f); hysteresis.update(); ut_assert_true(hysteresis.get_state());