mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-02-06 16:03:58 -04:00
AP_HAL_Linux: ignore unused result on panic
There's not much we can do if the write() call inside a panic function failed. Just ignore the failure.
This commit is contained in:
parent
8a58c06adb
commit
b687473174
@ -3,6 +3,7 @@
|
|||||||
#include <sys/time.h>
|
#include <sys/time.h>
|
||||||
#include <unistd.h>
|
#include <unistd.h>
|
||||||
|
|
||||||
|
#include <AP_Common/AP_Common.h>
|
||||||
#include <AP_HAL/AP_HAL.h>
|
#include <AP_HAL/AP_HAL.h>
|
||||||
#include <AP_HAL/system.h>
|
#include <AP_HAL/system.h>
|
||||||
#include <AP_HAL_Linux/Scheduler.h>
|
#include <AP_HAL_Linux/Scheduler.h>
|
||||||
@ -27,7 +28,7 @@ void panic(const char *errormsg, ...)
|
|||||||
va_start(ap, errormsg);
|
va_start(ap, errormsg);
|
||||||
vdprintf(1, errormsg, ap);
|
vdprintf(1, errormsg, ap);
|
||||||
va_end(ap);
|
va_end(ap);
|
||||||
write(1, "\n", 1);
|
UNUSED_RESULT(write(1, "\n", 1));
|
||||||
|
|
||||||
hal.rcin->deinit();
|
hal.rcin->deinit();
|
||||||
hal.scheduler->delay_microseconds(10000);
|
hal.scheduler->delay_microseconds(10000);
|
||||||
|
Loading…
Reference in New Issue
Block a user