mirror of https://github.com/ArduPilot/ardupilot
AP_HAL_ChibiOS: print linefeed after panic message
this makes the output much nicer and avoids including the linefeed in the caller
This commit is contained in:
parent
dc6c799dad
commit
72f56ee8fc
|
@ -335,6 +335,7 @@ void panic(const char *errormsg, ...)
|
|||
va_start(ap, errormsg);
|
||||
vprintf(errormsg, ap);
|
||||
va_end(ap);
|
||||
printf("\n");
|
||||
hal.scheduler->delay(delay_ms);
|
||||
delay_ms = 500;
|
||||
}
|
||||
|
|
Loading…
Reference in New Issue