mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-08 17:08:28 -04:00
DCM: renorm_sqrt_count is now called renorm_range_count
This commit is contained in:
parent
5cfe1ad5dc
commit
b231112957
@ -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);
|
||||
|
@ -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));
|
||||
|
@ -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;
|
||||
|
Loading…
Reference in New Issue
Block a user