mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-22 00:28:30 -04:00
Plane: trim out some log msgs on APM2
save a bit more flash
This commit is contained in:
parent
49f7adcc80
commit
9f9080983b
@ -152,7 +152,9 @@ void Plane::ahrs_update()
|
||||
|
||||
if (should_log(MASK_LOG_IMU)) {
|
||||
Log_Write_IMU();
|
||||
#if HAL_CPU_CLASS >= HAL_CPU_CLASS_75
|
||||
DataFlash.Log_Write_IMUDT(ins);
|
||||
#endif
|
||||
}
|
||||
|
||||
// calculate a scaled roll limit based on current pitch
|
||||
@ -255,8 +257,10 @@ void Plane::update_logging2(void)
|
||||
if (should_log(MASK_LOG_RC))
|
||||
Log_Write_RC();
|
||||
|
||||
#if HAL_CPU_CLASS >= HAL_CPU_CLASS_75
|
||||
if (should_log(MASK_LOG_IMU))
|
||||
DataFlash.Log_Write_Vibration(ins);
|
||||
#endif
|
||||
}
|
||||
|
||||
|
||||
@ -317,7 +321,9 @@ void Plane::one_second_loop()
|
||||
Log_Write_Status();
|
||||
}
|
||||
|
||||
#if HAL_CPU_CLASS >= HAL_CPU_CLASS_75
|
||||
ins.set_raw_logging(should_log(MASK_LOG_IMU_RAW));
|
||||
#endif
|
||||
}
|
||||
|
||||
void Plane::log_perf_info()
|
||||
@ -327,8 +333,10 @@ void Plane::log_perf_info()
|
||||
(unsigned long)G_Dt_max,
|
||||
(unsigned long)G_Dt_min);
|
||||
}
|
||||
#if HAL_CPU_CLASS >= HAL_CPU_CLASS_75
|
||||
if (should_log(MASK_LOG_PM))
|
||||
Log_Write_Performance();
|
||||
#endif
|
||||
G_Dt_max = 0;
|
||||
G_Dt_min = 0;
|
||||
resetPerfData();
|
||||
|
Loading…
Reference in New Issue
Block a user