mirror of https://github.com/ArduPilot/ardupilot
AP_HAL_ChibiOS: factor panic code to remove duplication
the code inside and above the loop are the same, it's just the delay which changes
This commit is contained in:
parent
d1cbf30286
commit
dc6c799dad
|
@ -330,16 +330,13 @@ void panic(const char *errormsg, ...)
|
|||
INTERNAL_ERROR(AP_InternalError::error_t::panic);
|
||||
va_list ap;
|
||||
|
||||
va_start(ap, errormsg);
|
||||
vprintf(errormsg, ap);
|
||||
va_end(ap);
|
||||
|
||||
hal.scheduler->delay_microseconds(10000);
|
||||
uint16_t delay_ms = 10000;
|
||||
while (1) {
|
||||
va_start(ap, errormsg);
|
||||
vprintf(errormsg, ap);
|
||||
va_end(ap);
|
||||
hal.scheduler->delay(500);
|
||||
hal.scheduler->delay(delay_ms);
|
||||
delay_ms = 500;
|
||||
}
|
||||
#else
|
||||
// we don't support variable args in bootlaoder
|
||||
|
|
Loading…
Reference in New Issue