From 4ec6a74829c79c898c44539baff385c7a6e635ec Mon Sep 17 00:00:00 2001 From: Andrew Tridgell Date: Tue, 2 Dec 2014 13:12:41 +1100 Subject: [PATCH] AP_HAL: addex UART_test example sketch --- libraries/AP_HAL/examples/UART_test/Makefile | 1 + .../AP_HAL/examples/UART_test/UART_test.pde | 100 ++++++++++++++++++ 2 files changed, 101 insertions(+) create mode 100644 libraries/AP_HAL/examples/UART_test/Makefile create mode 100644 libraries/AP_HAL/examples/UART_test/UART_test.pde diff --git a/libraries/AP_HAL/examples/UART_test/Makefile b/libraries/AP_HAL/examples/UART_test/Makefile new file mode 100644 index 0000000000..f5daf25151 --- /dev/null +++ b/libraries/AP_HAL/examples/UART_test/Makefile @@ -0,0 +1 @@ +include ../../../../mk/apm.mk diff --git a/libraries/AP_HAL/examples/UART_test/UART_test.pde b/libraries/AP_HAL/examples/UART_test/UART_test.pde new file mode 100644 index 0000000000..aab53c8f77 --- /dev/null +++ b/libraries/AP_HAL/examples/UART_test/UART_test.pde @@ -0,0 +1,100 @@ +/* + simple test of UART interfaces + */ +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include + +#if HAL_OS_POSIX_IO +#include +#endif + +const AP_HAL::HAL& hal = AP_HAL_BOARD_DRIVER; + +static AP_HAL::UARTDriver* uarts[] = { + hal.uartA, // console +}; +#define NUM_UARTS (sizeof(uarts)/sizeof(uarts[0])) + + +/* + setup one UART at 57600 + */ +static void setup_uart(AP_HAL::UARTDriver *uart, const char *name) +{ + if (uart == NULL) { + // that UART doesn't exist on this platform + return; + } + uart->begin(57600); +} + + +void setup(void) +{ + /* + start all UARTs at 57600 with default buffer sizes + */ + setup_uart(hal.uartA, "uartA"); // console + setup_uart(hal.uartB, "uartB"); // 1st GPS + setup_uart(hal.uartC, "uartC"); // telemetry 1 + setup_uart(hal.uartD, "uartD"); // telemetry 2 + setup_uart(hal.uartE, "uartE"); // 2nd GPS +} + +static void test_uart(AP_HAL::UARTDriver *uart, const char *name) +{ + if (uart == NULL) { + // that UART doesn't exist on this platform + return; + } + uart->printf("Hello on UART %s at %.3f seconds\n", + name, hal.scheduler->millis()*0.001f); +} + +void loop(void) +{ + test_uart(hal.uartA, "uartA"); + test_uart(hal.uartB, "uartB"); + test_uart(hal.uartC, "uartC"); + test_uart(hal.uartD, "uartD"); + test_uart(hal.uartE, "uartE"); + + // also do a raw printf() on some platforms, which prints to the + // debug console +#if HAL_OS_POSIX_IO + ::printf("Hello on debug console at %.3f seconds\n", hal.scheduler->millis()*0.001f); +#endif + + hal.scheduler->delay(1000); +} + +AP_HAL_MAIN();