mirror of https://github.com/ArduPilot/ardupilot
AP_Bootloader: disable debug printf
This commit is contained in:
parent
c36f677c94
commit
af78ac1abf
|
@ -25,6 +25,10 @@ static uint8_t last_uart;
|
|||
#define BOOTLOADER_BAUDRATE 115200
|
||||
#endif
|
||||
|
||||
// optional uprintf() code for debug
|
||||
// #define BOOTLOADER_DEBUG SD7
|
||||
|
||||
|
||||
// #pragma GCC optimize("O0")
|
||||
|
||||
int16_t cin(unsigned timeout_ms)
|
||||
|
@ -255,19 +259,19 @@ extern "C" {
|
|||
// printf to USB for debugging
|
||||
void uprintf(const char *fmt, ...)
|
||||
{
|
||||
#if HAL_USE_SERIAL_USB == TRUE
|
||||
#ifdef BOOTLOADER_DEBUG
|
||||
va_list ap;
|
||||
static bool initialised;
|
||||
char umsg[200];
|
||||
if (!initialised) {
|
||||
initialised = true;
|
||||
sercfg.speed = 57600;
|
||||
sdStart(&SD7, &sercfg);
|
||||
sdStart(&BOOTLOADER_DEBUG, &sercfg);
|
||||
}
|
||||
va_start(ap, fmt);
|
||||
uint32_t n = vsnprintf(umsg, sizeof(umsg), fmt, ap);
|
||||
va_end(ap);
|
||||
chnWriteTimeout(&SD7, (const uint8_t *)umsg, n, chTimeMS2I(100));
|
||||
chnWriteTimeout(&BOOTLOADER_DEBUG, (const uint8_t *)umsg, n, chTimeMS2I(100));
|
||||
#endif
|
||||
}
|
||||
|
||||
|
|
Loading…
Reference in New Issue