From 8911dfd791fcee69a2efd1d6c7b31552013a3f09 Mon Sep 17 00:00:00 2001 From: Holger Steinhaus Date: Sat, 31 Jan 2015 13:24:19 +0900 Subject: [PATCH] DataFlash: fix out-of-bounds read when logging Checked in my rmackay9 --- libraries/DataFlash/LogFile.cpp | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/libraries/DataFlash/LogFile.cpp b/libraries/DataFlash/LogFile.cpp index 373f5bf0ad..1d78dba5ac 100644 --- a/libraries/DataFlash/LogFile.cpp +++ b/libraries/DataFlash/LogFile.cpp @@ -837,7 +837,7 @@ void DataFlash_Class::Log_Write_IMU(const AP_InertialSensor &ins) accel_y : accel3.y, accel_z : accel3.z, gyro_error : ins.get_gyro_error_count(2), - accel_error : ins.get_accel_error_count(3) + accel_error : ins.get_accel_error_count(2) }; WriteBlock(&pkt3, sizeof(pkt3)); #endif