mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-03 06:28:27 -04:00
AP_HAL_Linux: check for alloc failure of ObjectBuffer
This commit is contained in:
parent
a99dd1fabf
commit
9154db9ae2
@ -171,6 +171,11 @@ void OpticalFlow_Onboard::init()
|
||||
}
|
||||
|
||||
_gyro_ring_buffer = new ObjectBuffer<GyroSample>(OPTICAL_FLOW_GYRO_BUFFER_LEN);
|
||||
if (_gyro_ring_buffer != nullptr && _gyro_ring_buffer->get_size() == 0) {
|
||||
// allocation failed
|
||||
delete _gyro_ring_buffer;
|
||||
_gyro_ring_buffer = nullptr;
|
||||
}
|
||||
|
||||
_initialized = true;
|
||||
}
|
||||
|
Loading…
Reference in New Issue
Block a user