mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-02-01 21:48:28 -04:00
AP_Bootloader: fixed build with no uarts
This commit is contained in:
parent
f71d2a7417
commit
0546ea69d1
@ -35,10 +35,6 @@ extern "C" {
|
|||||||
|
|
||||||
struct boardinfo board_info;
|
struct boardinfo board_info;
|
||||||
|
|
||||||
#ifndef BOOTLOADER_BAUDRATE
|
|
||||||
#define BOOTLOADER_BAUDRATE 115200
|
|
||||||
#endif
|
|
||||||
|
|
||||||
int main(void)
|
int main(void)
|
||||||
{
|
{
|
||||||
init_uarts();
|
init_uarts();
|
||||||
|
@ -14,10 +14,16 @@
|
|||||||
#include "mcu_f7.h"
|
#include "mcu_f7.h"
|
||||||
|
|
||||||
static BaseChannel *uarts[] = { BOOTLOADER_DEV_LIST };
|
static BaseChannel *uarts[] = { BOOTLOADER_DEV_LIST };
|
||||||
|
#if HAL_USE_SERIAL == TRUE
|
||||||
static SerialConfig sercfg;
|
static SerialConfig sercfg;
|
||||||
|
#endif
|
||||||
static int8_t locked_uart = -1;
|
static int8_t locked_uart = -1;
|
||||||
static uint8_t last_uart;
|
static uint8_t last_uart;
|
||||||
|
|
||||||
|
#ifndef BOOTLOADER_BAUDRATE
|
||||||
|
#define BOOTLOADER_BAUDRATE 115200
|
||||||
|
#endif
|
||||||
|
|
||||||
int16_t cin(unsigned timeout_ms)
|
int16_t cin(unsigned timeout_ms)
|
||||||
{
|
{
|
||||||
uint8_t b = 0;
|
uint8_t b = 0;
|
||||||
@ -328,6 +334,7 @@ void init_uarts(void)
|
|||||||
usbConnectBus(serusbcfg.usbp);
|
usbConnectBus(serusbcfg.usbp);
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
|
#if HAL_USE_SERIAL == TRUE
|
||||||
sercfg.speed = BOOTLOADER_BAUDRATE;
|
sercfg.speed = BOOTLOADER_BAUDRATE;
|
||||||
|
|
||||||
for (uint8_t i=0; i<ARRAY_SIZE_SIMPLE(uarts); i++) {
|
for (uint8_t i=0; i<ARRAY_SIZE_SIMPLE(uarts); i++) {
|
||||||
@ -338,6 +345,7 @@ void init_uarts(void)
|
|||||||
#endif
|
#endif
|
||||||
sdStart((SerialDriver *)uarts[i], &sercfg);
|
sdStart((SerialDriver *)uarts[i], &sercfg);
|
||||||
}
|
}
|
||||||
|
#endif
|
||||||
}
|
}
|
||||||
|
|
||||||
|
|
||||||
@ -352,8 +360,10 @@ void port_setbaud(uint32_t baudrate)
|
|||||||
return;
|
return;
|
||||||
}
|
}
|
||||||
#endif
|
#endif
|
||||||
|
#if HAL_USE_SERIAL == TRUE
|
||||||
memset(&sercfg, 0, sizeof(sercfg));
|
memset(&sercfg, 0, sizeof(sercfg));
|
||||||
sercfg.speed = baudrate;
|
sercfg.speed = baudrate;
|
||||||
sdStart((SerialDriver *)uarts[last_uart], &sercfg);
|
sdStart((SerialDriver *)uarts[last_uart], &sercfg);
|
||||||
|
#endif
|
||||||
}
|
}
|
||||||
|
|
||||||
|
Loading…
Reference in New Issue
Block a user