mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-09 09:28:31 -04:00
GCS_MAVLink: prevent segv in ftp
if the user disables ftp by changing BRD_OPTIONS after ftp has started then we could dereference a nullptr
This commit is contained in:
parent
781fed2390
commit
19d444bb3a
@ -181,7 +181,7 @@ void GCS_MAVLINK::ftp_worker(void) {
|
|||||||
while (true) {
|
while (true) {
|
||||||
bool skip_push_reply = false;
|
bool skip_push_reply = false;
|
||||||
|
|
||||||
while (!ftp.requests->pop(request)) {
|
while (ftp.requests == nullptr || !ftp.requests->pop(request)) {
|
||||||
// nothing to handle, delay ourselves a bit then check again. Ideally we'd use conditional waits here
|
// nothing to handle, delay ourselves a bit then check again. Ideally we'd use conditional waits here
|
||||||
hal.scheduler->delay(2);
|
hal.scheduler->delay(2);
|
||||||
}
|
}
|
||||||
|
Loading…
Reference in New Issue
Block a user