From 1b152cf2bf551ea023219402c390caaf26af1e19 Mon Sep 17 00:00:00 2001 From: Robert Lefebvre Date: Thu, 18 Dec 2014 16:35:23 -0500 Subject: [PATCH] ArduCopter: Change Current logging to use common-vehicle logging in DataFlash library. --- ArduCopter/Log.pde | 27 ++------------------------- ArduCopter/defines.h | 1 - 2 files changed, 2 insertions(+), 26 deletions(-) diff --git a/ArduCopter/Log.pde b/ArduCopter/Log.pde index 177eb0416f..7f8d07ada0 100644 --- a/ArduCopter/Log.pde +++ b/ArduCopter/Log.pde @@ -207,31 +207,10 @@ static void Log_Write_AutoTuneDetails(int16_t angle_cd, float rate_cds) } #endif -struct PACKED log_Current { - LOG_PACKET_HEADER; - uint32_t time_ms; - int16_t throttle_out; - uint32_t throttle_integrator; - int16_t battery_voltage; - int16_t current_amps; - uint16_t board_voltage; - float current_total; -}; - -// Write an Current data packet +// Write a Current data packet static void Log_Write_Current() { - struct log_Current pkt = { - LOG_PACKET_HEADER_INIT(LOG_CURRENT_MSG), - time_ms : hal.scheduler->millis(), - throttle_out : g.rc_3.servo_out, - throttle_integrator : throttle_integrator, - battery_voltage : (int16_t) (battery.voltage() * 100.0f), - current_amps : (int16_t) (battery.current_amps() * 100.0f), - board_voltage : (uint16_t)(hal.analogin->board_voltage()*1000), - current_total : battery.current_total_mah() - }; - DataFlash.WriteBlock(&pkt, sizeof(pkt)); + DataFlash.Log_Write_Current(battery, g.rc_3.servo_out); // also write power status DataFlash.Log_Write_Power(); @@ -651,8 +630,6 @@ static const struct LogStructure log_structure[] PROGMEM = { { LOG_AUTOTUNEDETAILS_MSG, sizeof(log_AutoTuneDetails), "ATDE", "cf", "Angle,Rate" }, #endif - { LOG_CURRENT_MSG, sizeof(log_Current), - "CURR", "IhIhhhf", "TimeMS,ThrOut,ThrInt,Volt,Curr,Vcc,CurrTot" }, { LOG_OPTFLOW_MSG, sizeof(log_Optflow), "OF", "IBffff", "TimeMS,Qual,flowX,flowY,bodyX,bodyY" }, { LOG_NAV_TUNING_MSG, sizeof(log_Nav_Tuning), diff --git a/ArduCopter/defines.h b/ArduCopter/defines.h index db6d9d35c3..d0c56cd8ec 100644 --- a/ArduCopter/defines.h +++ b/ArduCopter/defines.h @@ -222,7 +222,6 @@ enum FlipState { #define LOG_CONTROL_TUNING_MSG 0x04 #define LOG_NAV_TUNING_MSG 0x05 #define LOG_PERFORMANCE_MSG 0x06 -#define LOG_CURRENT_MSG 0x09 #define LOG_STARTUP_MSG 0x0A #define LOG_OPTFLOW_MSG 0x0C #define LOG_EVENT_MSG 0x0D