mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-02-21 23:33:57 -04:00
AP_HAL_ChibiOS: use HAL_SERIAL0_BAUD_DEFAULT when setting up serial(0)
This commit is contained in:
parent
cc02ad9224
commit
2ac7dcc764
@ -38,6 +38,10 @@
|
||||
|
||||
#include <hwdef.h>
|
||||
|
||||
#ifndef HAL_SERIAL0_BAUD_DEFAULT
|
||||
#define HAL_SERIAL0_BAUD_DEFAULT 115200
|
||||
#endif
|
||||
|
||||
#ifndef HAL_NO_UARTDRIVER
|
||||
static HAL_UARTA_DRIVER;
|
||||
static HAL_UARTB_DRIVER;
|
||||
@ -219,7 +223,7 @@ static void main_loop()
|
||||
|
||||
peripheral_power_enable();
|
||||
|
||||
hal.serial(0)->begin(115200);
|
||||
hal.serial(0)->begin(HAL_SERIAL0_BAUD_DEFAULT);
|
||||
|
||||
#ifdef HAL_SPI_CHECK_CLOCK_FREQ
|
||||
// optional test of SPI clock frequencies
|
||||
|
Loading…
Reference in New Issue
Block a user