Files
bizhang_-obav/src/systemcmds/tests/test_hysteresis.cpp
Mara Bos e9fb17c51a Always use FILE* for standard output.
The threads running commands for clients through the Posix daemon used
to write to a char buffer through snprintf (etc.) which was then written
directly to the file descriptor, whereas in the other case printf
(etc.) was used to write to stdout (FILE*). Both versions used some
macro's and repeated code to have the same output.

This change unifies these two cases by using a FILE* in both cases. The
(line) buffering is done by the standard C library's implementation
(just like with stdout), and px4_log.c now uses the same code in all
cases (using fprintf, etc.) for printing (colored) output.
2018-11-23 12:15:41 +01:00

206 lines
4.9 KiB
C++

#include <unit_test.h>
#include <unistd.h>
#include <systemlib/hysteresis/hysteresis.h>
class HysteresisTest : public UnitTest
{
public:
virtual bool run_tests();
private:
bool _init_false();
bool _init_true();
bool _zero_case();
bool _change_after_time();
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()
{
ut_run_test(_init_false);
ut_run_test(_init_true);
ut_run_test(_zero_case);
ut_run_test(_change_after_time);
ut_run_test(_hysteresis_changed);
ut_run_test(_change_after_multiple_sets);
ut_run_test(_take_change_back);
return (_tests_failed == 0);
}
bool HysteresisTest::_init_false()
{
systemlib::Hysteresis hysteresis(false);
ut_assert_false(hysteresis.get_state());
return true;
}
bool HysteresisTest::_init_true()
{
systemlib::Hysteresis hysteresis(true);
ut_assert_true(hysteresis.get_state());
return true;
}
bool HysteresisTest::_zero_case()
{
// Default is 0 hysteresis.
systemlib::Hysteresis hysteresis(false);
ut_assert_false(hysteresis.get_state());
// Change and see result immediately.
hysteresis.set_state_and_update(true);
ut_assert_true(hysteresis.get_state());
hysteresis.set_state_and_update(false);
ut_assert_false(hysteresis.get_state());
hysteresis.set_state_and_update(true);
ut_assert_true(hysteresis.get_state());
// A wait won't change anything.
usleep(1000 * f);
hysteresis.update();
ut_assert_true(hysteresis.get_state());
return true;
}
bool HysteresisTest::_change_after_time()
{
systemlib::Hysteresis hysteresis(false);
hysteresis.set_hysteresis_time_from(false, 5000 * f);
hysteresis.set_hysteresis_time_from(true, 3000 * f);
// Change to true.
hysteresis.set_state_and_update(true);
ut_assert_false(hysteresis.get_state());
usleep(4000 * f);
hysteresis.update();
ut_assert_false(hysteresis.get_state());
usleep(2000 * f);
hysteresis.update();
ut_assert_true(hysteresis.get_state());
// Change back to false.
hysteresis.set_state_and_update(false);
ut_assert_true(hysteresis.get_state());
usleep(1000 * f);
hysteresis.update();
ut_assert_true(hysteresis.get_state());
usleep(3000 * f);
hysteresis.update();
ut_assert_false(hysteresis.get_state());
return true;
}
bool HysteresisTest::_hysteresis_changed()
{
systemlib::Hysteresis hysteresis(false);
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 * f);
hysteresis.update();
ut_assert_false(hysteresis.get_state());
usleep(3000 * f);
hysteresis.update();
ut_assert_true(hysteresis.get_state());
// Change hysteresis time.
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 * f);
hysteresis.update();
ut_assert_true(hysteresis.get_state());
usleep(5000 * f);
hysteresis.update();
ut_assert_false(hysteresis.get_state());
return true;
}
bool HysteresisTest::_change_after_multiple_sets()
{
systemlib::Hysteresis hysteresis(false);
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 * f);
hysteresis.set_state_and_update(true);
ut_assert_false(hysteresis.get_state());
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 * f);
hysteresis.set_state_and_update(false);
ut_assert_true(hysteresis.get_state());
usleep(3000 * f);
hysteresis.set_state_and_update(false);
ut_assert_false(hysteresis.get_state());
return true;
}
bool HysteresisTest::_take_change_back()
{
systemlib::Hysteresis hysteresis(false);
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 * 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 * 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 * f);
hysteresis.update();
ut_assert_false(hysteresis.get_state());
usleep(3000 * f);
hysteresis.update();
ut_assert_true(hysteresis.get_state());
// The other directory is immediate.
hysteresis.set_state_and_update(false);
ut_assert_false(hysteresis.get_state());
return true;
}
ut_declare_test_c(test_hysteresis, HysteresisTest)