mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-09 01:18:29 -04:00
DataFlash: fix out-of-bounds read when logging
Checked in my rmackay9
This commit is contained in:
parent
0d94d5441f
commit
8911dfd791
@ -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
|
||||
|
Loading…
Reference in New Issue
Block a user