mirror of https://github.com/ArduPilot/ardupilot
AC_Avoidance: check for alloc failure of ObjectBuffer
This commit is contained in:
parent
bbee8312dd
commit
a99dd1fabf
|
@ -186,6 +186,11 @@ void AP_OADatabase::init_queue()
|
|||
}
|
||||
|
||||
_queue.items = new ObjectBuffer<OA_DbItem>(_queue.size);
|
||||
if (_queue.items != nullptr && _queue.items->get_size() == 0) {
|
||||
// allocation failed
|
||||
delete _queue.items;
|
||||
_queue.items = nullptr;
|
||||
}
|
||||
}
|
||||
|
||||
void AP_OADatabase::init_database()
|
||||
|
|
Loading…
Reference in New Issue