ardupilot/libraries/AP_HAL/examples/UART_test/UART_test.cpp

Ignoring revisions in .git-blame-ignore-revs. Click here to bypass and see the normal blame view.

68 lines
1.6 KiB
C++
Raw Normal View History

2014-12-01 22:12:41 -04:00
/*
simple test of UART interfaces
*/
#include <AP_HAL/AP_HAL.h>
2014-12-01 22:12:41 -04:00
#include <stdio.h>
void setup();
void loop();
const AP_HAL::HAL& hal = AP_HAL::get_HAL();
2014-12-01 22:12:41 -04:00
/*
setup one UART at 57600
*/
static void setup_uart(AP_HAL::UARTDriver *uart, const char *name)
{
if (uart == nullptr) {
2014-12-01 22:12:41 -04:00
// that UART doesn't exist on this platform
return;
}
uart->begin(57600);
}
void setup(void)
2014-12-01 22:12:41 -04:00
{
/*
start all UARTs at 57600 with default buffer sizes
*/
hal.scheduler->delay(1000); //Ensure that hal.serial(n) can be initialized
setup_uart(hal.serial(0), "SERIAL0"); // console
setup_uart(hal.serial(1), "SERIAL1"); // telemetry 1
setup_uart(hal.serial(2), "SERIAL2"); // telemetry 2
setup_uart(hal.serial(3), "SERIAL3"); // 1st GPS
setup_uart(hal.serial(4), "SERIAL4"); // 2nd GPS
2014-12-01 22:12:41 -04:00
}
static void test_uart(AP_HAL::UARTDriver *uart, const char *name)
{
if (uart == nullptr) {
2014-12-01 22:12:41 -04:00
// that UART doesn't exist on this platform
return;
}
uart->printf("Hello on UART %s at %.3f seconds\n",
name, (double)(AP_HAL::millis() * 0.001f));
2014-12-01 22:12:41 -04:00
}
void loop(void)
{
test_uart(hal.serial(0), "SERIAL0");
test_uart(hal.serial(1), "SERIAL1");
test_uart(hal.serial(2), "SERIAL2");
test_uart(hal.serial(3), "SERIAL3");
test_uart(hal.serial(4), "SERIAL4");
2014-12-01 22:12:41 -04:00
// also do a raw printf() on some platforms, which prints to the
// debug console
::printf("Hello on debug console at %.3f seconds\n", (double)(AP_HAL::millis() * 0.001f));
2014-12-01 22:12:41 -04:00
hal.scheduler->delay(1000);
}
AP_HAL_MAIN();