diff --git a/libraries/DataFlash/DataFlash.h b/libraries/DataFlash/DataFlash.h index 97132e3015..bc689396c9 100644 --- a/libraries/DataFlash/DataFlash.h +++ b/libraries/DataFlash/DataFlash.h @@ -136,7 +136,7 @@ public: void Log_Write_ESC(void); void Log_Write_Airspeed(AP_Airspeed &airspeed); void Log_Write_Attitude(AP_AHRS &ahrs, const Vector3f &targets); - void Log_Write_Current(const AP_BattMonitor &battery, int16_t throttle); + void Log_Write_Current(const AP_BattMonitor &battery); void Log_Write_Compass(const Compass &compass, uint64_t time_us=0); void Log_Write_Mode(uint8_t mode, uint8_t reason = 0); diff --git a/libraries/DataFlash/LogFile.cpp b/libraries/DataFlash/LogFile.cpp index b623cd63a5..14d77815c1 100644 --- a/libraries/DataFlash/LogFile.cpp +++ b/libraries/DataFlash/LogFile.cpp @@ -1638,7 +1638,7 @@ void DataFlash_Class::Log_Write_Attitude(AP_AHRS &ahrs, const Vector3f &targets) } // Write an Current data packet -void DataFlash_Class::Log_Write_Current(const AP_BattMonitor &battery, int16_t throttle) +void DataFlash_Class::Log_Write_Current(const AP_BattMonitor &battery) { float voltage2 = battery.voltage2(); struct log_Current pkt = {