From 06da2f50cef4fdcb6491dd046f112baaa8b2b9ff Mon Sep 17 00:00:00 2001 From: Peter Barker Date: Thu, 22 Feb 2018 10:47:31 +1100 Subject: [PATCH] Copter: correct compilation when logging is disabled --- ArduCopter/Log.cpp | 4 ---- ArduCopter/mode.h | 2 ++ 2 files changed, 2 insertions(+), 4 deletions(-) diff --git a/ArduCopter/Log.cpp b/ArduCopter/Log.cpp index 268201d9c6..be481e8551 100644 --- a/ArduCopter/Log.cpp +++ b/ArduCopter/Log.cpp @@ -654,10 +654,6 @@ void Copter::log_init(void) #else // LOGGING_ENABLED -void Copter::Log_Write_AutoTune(uint8_t axis, uint8_t tune_step, float meas_target, \ - float meas_min, float meas_max, float new_gain_rp, \ - float new_gain_rd, float new_gain_sp, float new_ddt) {} -void Copter::Log_Write_AutoTuneDetails(float angle_cd, float rate_cds) {} void Copter::Log_Write_Nav_Tuning() {} void Copter::Log_Write_Control_Tuning() {} void Copter::Log_Write_Performance() {} diff --git a/ArduCopter/mode.h b/ArduCopter/mode.h index d7db11273e..6e0f4a364a 100644 --- a/ArduCopter/mode.h +++ b/ArduCopter/mode.h @@ -368,8 +368,10 @@ private: void twitching_measure_acceleration(float &rate_of_change, float rate_measurement, float &rate_measurement_max); void get_poshold_attitude(float &roll_cd, float &pitch_cd, float &yaw_cd); +#if LOGGING_ENABLED == ENABLED void Log_Write_AutoTune(uint8_t axis, uint8_t tune_step, float meas_target, float meas_min, float meas_max, float new_gain_rp, float new_gain_rd, float new_gain_sp, float new_ddt); void Log_Write_AutoTuneDetails(float angle_cd, float rate_cds); +#endif void send_step_string(); const char *level_issue_string() const;