mirror of https://github.com/ArduPilot/ardupilot
AP_HAL_Linux: check for alloc failure of ObjectBuffer
This commit is contained in:
parent
c6e7abf247
commit
23ea7710b1
|
@ -171,6 +171,11 @@ void OpticalFlow_Onboard::init()
|
||||||
}
|
}
|
||||||
|
|
||||||
_gyro_ring_buffer = new ObjectBuffer<GyroSample>(OPTICAL_FLOW_GYRO_BUFFER_LEN);
|
_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;
|
_initialized = true;
|
||||||
}
|
}
|
||||||
|
|
Loading…
Reference in New Issue