mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-02-09 09:24:01 -04:00
HAL_ChibiOS: fixed panic to output error every 500ms
This commit is contained in:
parent
a733690f80
commit
58e915155d
@ -29,6 +29,9 @@
|
|||||||
#include <ctype.h>
|
#include <ctype.h>
|
||||||
#include "hwdef/common/stdio.h"
|
#include "hwdef/common/stdio.h"
|
||||||
#include <AP_HAL/AP_HAL.h>
|
#include <AP_HAL/AP_HAL.h>
|
||||||
|
#if HAL_USE_SERIAL_USB == TRUE
|
||||||
|
#include <AP_HAL_ChibiOS/hwdef/common/usbcfg.h>
|
||||||
|
#endif
|
||||||
|
|
||||||
extern const AP_HAL::HAL& hal;
|
extern const AP_HAL::HAL& hal;
|
||||||
|
|
||||||
@ -80,7 +83,9 @@ int __wrap_asprintf(char **strp, const char *fmt, ...)
|
|||||||
int __wrap_vprintf(const char *fmt, va_list arg)
|
int __wrap_vprintf(const char *fmt, va_list arg)
|
||||||
{
|
{
|
||||||
#ifdef HAL_STDOUT_SERIAL
|
#ifdef HAL_STDOUT_SERIAL
|
||||||
return chvprintf ((BaseSequentialStream*)&HAL_STDOUT_SERIAL, fmt, arg);
|
return chvprintf((BaseSequentialStream*)&HAL_STDOUT_SERIAL, fmt, arg);
|
||||||
|
#elif HAL_USE_SERIAL_USB == TRUE
|
||||||
|
return chvprintf((BaseSequentialStream*)&SDU1, fmt, arg);
|
||||||
#else
|
#else
|
||||||
(void)arg;
|
(void)arg;
|
||||||
return strlen(fmt);
|
return strlen(fmt);
|
||||||
|
@ -203,7 +203,10 @@ void panic(const char *errormsg, ...)
|
|||||||
va_end(ap);
|
va_end(ap);
|
||||||
|
|
||||||
hal.scheduler->delay_microseconds(10000);
|
hal.scheduler->delay_microseconds(10000);
|
||||||
while(1) {}
|
while (1) {
|
||||||
|
vprintf(errormsg, ap);
|
||||||
|
hal.scheduler->delay(500);
|
||||||
|
}
|
||||||
}
|
}
|
||||||
|
|
||||||
uint32_t micros()
|
uint32_t micros()
|
||||||
|
Loading…
Reference in New Issue
Block a user