|
|
|
@ -34,11 +34,11 @@ void setup(void)
@@ -34,11 +34,11 @@ void setup(void)
|
|
|
|
|
|
|
|
|
|
hal.scheduler->delay(1000); //Ensure that the uartA can be initialized
|
|
|
|
|
|
|
|
|
|
setup_uart(hal.serial(0), "uartA"); // console
|
|
|
|
|
setup_uart(hal.serial(3), "uartB"); // 1st GPS
|
|
|
|
|
setup_uart(hal.serial(1), "uartC"); // telemetry 1
|
|
|
|
|
setup_uart(hal.serial(2), "uartD"); // telemetry 2
|
|
|
|
|
setup_uart(hal.serial(3), "uartE"); // 2nd GPS
|
|
|
|
|
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
|
|
|
|
|
} |
|
|
|
|
|
|
|
|
|
static void test_uart(AP_HAL::UARTDriver *uart, const char *name) |
|
|
|
@ -53,11 +53,11 @@ static void test_uart(AP_HAL::UARTDriver *uart, const char *name)
@@ -53,11 +53,11 @@ static void test_uart(AP_HAL::UARTDriver *uart, const char *name)
|
|
|
|
|
|
|
|
|
|
void loop(void) |
|
|
|
|
{ |
|
|
|
|
test_uart(hal.serial(0), "uartA"); |
|
|
|
|
test_uart(hal.serial(3), "uartB"); |
|
|
|
|
test_uart(hal.serial(1), "uartC"); |
|
|
|
|
test_uart(hal.serial(2), "uartD"); |
|
|
|
|
test_uart(hal.serial(3), "uartE"); |
|
|
|
|
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"); |
|
|
|
|
|
|
|
|
|
// also do a raw printf() on some platforms, which prints to the
|
|
|
|
|
// debug console
|
|
|
|
|