From b231112957609356340cdc8c30cf9c897e99483e Mon Sep 17 00:00:00 2001 From: Andrew Tridgell Date: Fri, 17 Feb 2012 16:15:51 +1100 Subject: [PATCH] DCM: renorm_sqrt_count is now called renorm_range_count --- ArduCopter/Log.pde | 2 +- ArduPlane/Log.pde | 2 +- ArduPlane/system.pde | 2 +- 3 files changed, 3 insertions(+), 3 deletions(-) diff --git a/ArduCopter/Log.pde b/ArduCopter/Log.pde index 3833f4eb24..4866b15a9d 100644 --- a/ArduCopter/Log.pde +++ b/ArduCopter/Log.pde @@ -619,7 +619,7 @@ static void Log_Write_Performance() DataFlash.WriteByte(LOG_PERFORMANCE_MSG); DataFlash.WriteByte( dcm.gyro_sat_count); //1 DataFlash.WriteByte( imu.adc_constraints); //2 - DataFlash.WriteByte( dcm.renorm_sqrt_count); //3 + DataFlash.WriteByte( dcm.renorm_range_count); //3 DataFlash.WriteByte( dcm.renorm_blowup_count); //4 DataFlash.WriteByte( gps_fix_count); //5 DataFlash.WriteByte(END_BYTE); diff --git a/ArduPlane/Log.pde b/ArduPlane/Log.pde index da073b0873..5c7883a83e 100644 --- a/ArduPlane/Log.pde +++ b/ArduPlane/Log.pde @@ -241,7 +241,7 @@ static void Log_Write_Performance() DataFlash.WriteInt(G_Dt_max); DataFlash.WriteByte(dcm.gyro_sat_count); DataFlash.WriteByte(imu.adc_constraints); - DataFlash.WriteByte(dcm.renorm_sqrt_count); + DataFlash.WriteByte(dcm.renorm_range_count); DataFlash.WriteByte(dcm.renorm_blowup_count); DataFlash.WriteByte(gps_fix_count); DataFlash.WriteInt((int)(dcm.get_health() * 1000)); diff --git a/ArduPlane/system.pde b/ArduPlane/system.pde index 37d8fb17a2..2224508ee5 100644 --- a/ArduPlane/system.pde +++ b/ArduPlane/system.pde @@ -509,7 +509,7 @@ static void resetPerfData(void) { G_Dt_max = 0; dcm.gyro_sat_count = 0; imu.adc_constraints = 0; - dcm.renorm_sqrt_count = 0; + dcm.renorm_range_count = 0; dcm.renorm_blowup_count = 0; gps_fix_count = 0; pmTest1 = 0;