DataFlash: fix out-of-bounds read when logging

Checked in my rmackay9
This commit is contained in:
Holger Steinhaus 2015-01-31 13:24:19 +09:00 committed by Randy Mackay
parent 0d94d5441f
commit 8911dfd791
1 changed files with 1 additions and 1 deletions

View File

@ -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