Browse Source

Copter: correct compilation when logging is disabled

master
Peter Barker 7 years ago committed by Randy Mackay
parent
commit
06da2f50ce
  1. 4
      ArduCopter/Log.cpp
  2. 2
      ArduCopter/mode.h

4
ArduCopter/Log.cpp

@ -654,10 +654,6 @@ void Copter::log_init(void) @@ -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() {}

2
ArduCopter/mode.h

@ -368,8 +368,10 @@ private: @@ -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;

Loading…
Cancel
Save