diff --git a/libraries/AP_GyroFFT/AP_GyroFFT.cpp b/libraries/AP_GyroFFT/AP_GyroFFT.cpp index 886baa3749..5a1c0e7966 100644 --- a/libraries/AP_GyroFFT/AP_GyroFFT.cpp +++ b/libraries/AP_GyroFFT/AP_GyroFFT.cpp @@ -473,7 +473,7 @@ uint16_t AP_GyroFFT::run_cycle() _thread_state._last_output_us[_update_axis] = AP_HAL::micros(); _output_cycle_micros = _thread_state._last_output_us[_update_axis] - now; -#if AP_SIM_ENABLED +#if AP_SIM_ENABLED && HAL_LOGGING_ENABLED // extra logging when running simulations AP::logger().WriteStreaming( "FTN3", @@ -966,6 +966,8 @@ float AP_GyroFFT::calculate_weighted_freq_hz(const Vector3f& energy, const Vecto // @Field: FHZ: FFT health, Z-axis // @Field: Tc: FFT cycle time +#if HAL_LOGGING_ENABLED + // log gyro fft messages void AP_GyroFFT::write_log_messages() { @@ -1048,6 +1050,8 @@ void AP_GyroFFT::log_noise_peak(uint8_t id, FrequencyPeak peak) const get_center_freq_energy(peak).z); } +#endif + // return an average noise bandwidth weighted by bin energy // called from main thread float AP_GyroFFT::get_weighted_noise_center_bandwidth_hz() const