Browse Source

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
c415-sdk
Andrew Tridgell 4 years ago committed by Peter Barker
parent
commit
03f2e853ce
  1. 3
      libraries/AP_NavEKF3/AP_NavEKF3_Buffer.h

3
libraries/AP_NavEKF3/AP_NavEKF3_Buffer.h

@ -85,6 +85,9 @@ public: @@ -85,6 +85,9 @@ public:
*/
inline void push(element_type element)
{
if (buffer == nullptr) {
return;
}
// Advance head to next available index
_head = (_head+1)%_size;
// New data is written at the head

Loading…
Cancel
Save