mirror of https://github.com/ArduPilot/ardupilot
AP_NavEKF3: fixed memory corruption on push before init
this fixes a bug that happens with VISION_SPEED_ESTIMATE from a companion computer, which may come in before the EKF buffers are allocated. That causes a push to an uninitialised ringbuffer which triggers memory corruption found using the new memory guard system
This commit is contained in:
parent
a86734171c
commit
82ae3fe635
|
@ -85,6 +85,9 @@ public:
|
||||||
*/
|
*/
|
||||||
inline void push(element_type element)
|
inline void push(element_type element)
|
||||||
{
|
{
|
||||||
|
if (buffer == nullptr) {
|
||||||
|
return;
|
||||||
|
}
|
||||||
// Advance head to next available index
|
// Advance head to next available index
|
||||||
_head = (_head+1)%_size;
|
_head = (_head+1)%_size;
|
||||||
// New data is written at the head
|
// New data is written at the head
|
||||||
|
|
Loading…
Reference in New Issue