mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-24 01:28:29 -04:00
AP_HAL: convert to using hal.serial() instead of hal.uartX
This commit is contained in:
parent
e54fc4b0de
commit
95c0852b13
@ -41,14 +41,14 @@ void setup(void)
|
|||||||
hal.scheduler->delay(1000); //Ensure that the uartA can be initialized
|
hal.scheduler->delay(1000); //Ensure that the uartA can be initialized
|
||||||
|
|
||||||
#if CONFIG_HAL_BOARD == HAL_BOARD_LINUX
|
#if CONFIG_HAL_BOARD == HAL_BOARD_LINUX
|
||||||
uart = hal.uartA; // console
|
uart = hal.serial(0); // console
|
||||||
#endif
|
#endif
|
||||||
// uart = hal.uartB; // 1st GPS
|
// uart = hal.serial(3); // 1st GPS
|
||||||
#if CONFIG_HAL_BOARD == HAL_BOARD_CHIBIOS
|
#if CONFIG_HAL_BOARD == HAL_BOARD_CHIBIOS
|
||||||
uart = hal.uartC; // telemetry 1
|
uart = hal.serial(1); // telemetry 1
|
||||||
#endif
|
#endif
|
||||||
// uart = hal.uartD; // telemetry 2
|
// uart = hal.serial(2); // telemetry 2
|
||||||
// uart = hal.uartE; // 2nd GPS
|
// uart = hal.serial(4); // 2nd GPS
|
||||||
|
|
||||||
|
|
||||||
if (uart == nullptr) {
|
if (uart == nullptr) {
|
||||||
|
@ -34,11 +34,11 @@ void setup(void)
|
|||||||
|
|
||||||
hal.scheduler->delay(1000); //Ensure that the uartA can be initialized
|
hal.scheduler->delay(1000); //Ensure that the uartA can be initialized
|
||||||
|
|
||||||
setup_uart(hal.uartA, "uartA"); // console
|
setup_uart(hal.serial(0), "uartA"); // console
|
||||||
setup_uart(hal.uartB, "uartB"); // 1st GPS
|
setup_uart(hal.serial(3), "uartB"); // 1st GPS
|
||||||
setup_uart(hal.uartC, "uartC"); // telemetry 1
|
setup_uart(hal.serial(1), "uartC"); // telemetry 1
|
||||||
setup_uart(hal.uartD, "uartD"); // telemetry 2
|
setup_uart(hal.serial(2), "uartD"); // telemetry 2
|
||||||
setup_uart(hal.uartE, "uartE"); // 2nd GPS
|
setup_uart(hal.serial(3), "uartE"); // 2nd GPS
|
||||||
}
|
}
|
||||||
|
|
||||||
static void test_uart(AP_HAL::UARTDriver *uart, const char *name)
|
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)
|
void loop(void)
|
||||||
{
|
{
|
||||||
test_uart(hal.uartA, "uartA");
|
test_uart(hal.serial(0), "uartA");
|
||||||
test_uart(hal.uartB, "uartB");
|
test_uart(hal.serial(3), "uartB");
|
||||||
test_uart(hal.uartC, "uartC");
|
test_uart(hal.serial(1), "uartC");
|
||||||
test_uart(hal.uartD, "uartD");
|
test_uart(hal.serial(2), "uartD");
|
||||||
test_uart(hal.uartE, "uartE");
|
test_uart(hal.serial(3), "uartE");
|
||||||
|
|
||||||
// also do a raw printf() on some platforms, which prints to the
|
// also do a raw printf() on some platforms, which prints to the
|
||||||
// debug console
|
// debug console
|
||||||
|
Loading…
Reference in New Issue
Block a user