From 9b81e46e61accd1e0ed2638351857c16b9477b61 Mon Sep 17 00:00:00 2001 From: Randy Mackay Date: Wed, 11 Jun 2014 16:17:44 +0900 Subject: [PATCH] AP_Common: add example sketch --- .../examples/AP_Common/AP_Common.pde | 54 +++++++++++++++++++ 1 file changed, 54 insertions(+) create mode 100644 libraries/AP_Common/examples/AP_Common/AP_Common.pde diff --git a/libraries/AP_Common/examples/AP_Common/AP_Common.pde b/libraries/AP_Common/examples/AP_Common/AP_Common.pde new file mode 100644 index 0000000000..e98ccd8146 --- /dev/null +++ b/libraries/AP_Common/examples/AP_Common/AP_Common.pde @@ -0,0 +1,54 @@ +/// -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*- +// +// Unit tests for the AP_Common code +// + +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include + +const AP_HAL::HAL& hal = AP_HAL_BOARD_DRIVER; + +void test_high_low_byte(void) +{ + uint16_t i; + uint8_t high, low; + + // test each value from 0 to 300 + for (i=0; i<=300; i++) { + high = HIGHBYTE(i); + low = LOWBYTE(i); + hal.console->printf_P(PSTR("\ni:%u high:%u low:%u"),(unsigned int)i, (unsigned int)high, (unsigned int)low); + } + + // test values from 300 to 65400 at increments of 200 + for (i=301; i<=65400; i+=200) { + high = HIGHBYTE(i); + low = LOWBYTE(i); + hal.console->printf_P(PSTR("\ni:%u high:%u low:%u"),(unsigned int)i, (unsigned int)high, (unsigned int)low); + } +} + +/* + * euler angle tests + */ +void setup(void) +{ + hal.console->println("AP_Common tests\n"); + + test_high_low_byte(); +} + +void loop(void) +{ + // do nothing +} + +AP_HAL_MAIN();