From a2d73b42b910e00c79298bea00bcb1f5fa64f57a Mon Sep 17 00:00:00 2001 From: Robert Lefebvre Date: Fri, 16 Jan 2015 11:30:49 -0500 Subject: [PATCH] Plane: Change Mode logging to use DataFlash library method. --- ArduPlane/Log.pde | 21 --------------------- ArduPlane/commands_logic.pde | 2 +- ArduPlane/system.pde | 2 +- 3 files changed, 2 insertions(+), 23 deletions(-) diff --git a/ArduPlane/Log.pde b/ArduPlane/Log.pde index 560dd1d3e8..7e746cbca2 100644 --- a/ArduPlane/Log.pde +++ b/ArduPlane/Log.pde @@ -316,25 +316,6 @@ static void Log_Write_Nav_Tuning() DataFlash.WriteBlock(&pkt, sizeof(pkt)); } -struct PACKED log_Mode { - LOG_PACKET_HEADER; - uint32_t time_ms; - uint8_t mode; - uint8_t mode_num; -}; - -// Write a mode packet. Total length : 5 bytes -static void Log_Write_Mode(uint8_t mode) -{ - struct log_Mode pkt = { - LOG_PACKET_HEADER_INIT(LOG_MODE_MSG), - time_ms : hal.scheduler->millis(), - mode : mode, - mode_num : mode - }; - DataFlash.WriteBlock(&pkt, sizeof(pkt)); -} - struct PACKED log_Sonar { LOG_PACKET_HEADER; uint32_t timestamp; @@ -524,8 +505,6 @@ static const struct LogStructure log_structure[] PROGMEM = { "NTUN", "ICfccccfI", "TimeMS,Yaw,WpDist,TargBrg,NavBrg,AltErr,Arspd,Alt,GSpdCM" }, { LOG_SONAR_MSG, sizeof(log_Sonar), "SONR", "IffffBBf", "TimeMS,DistCM,Volt,BaroAlt,GSpd,Thr,Cnt,Corr" }, - { LOG_MODE_MSG, sizeof(log_Mode), - "MODE", "IMB", "TimeMS,Mode,ModeNum" }, { LOG_COMPASS_MSG, sizeof(log_Compass), "MAG", "Ihhhhhh", "TimeMS,MagX,MagY,MagZ,OfsX,OfsY,OfsZ" }, { LOG_COMPASS2_MSG, sizeof(log_Compass), diff --git a/ArduPlane/commands_logic.pde b/ArduPlane/commands_logic.pde index 58017f24bd..07a981973c 100644 --- a/ArduPlane/commands_logic.pde +++ b/ArduPlane/commands_logic.pde @@ -299,7 +299,7 @@ static void do_RTL(void) setup_turn_angle(); if (should_log(MASK_LOG_MODE)) - Log_Write_Mode(control_mode); + DataFlash.Log_Write_Mode(control_mode); } static void do_takeoff(const AP_Mission::Mission_Command& cmd) diff --git a/ArduPlane/system.pde b/ArduPlane/system.pde index ee122db702..1af451051a 100644 --- a/ArduPlane/system.pde +++ b/ArduPlane/system.pde @@ -404,7 +404,7 @@ static void set_mode(enum FlightMode mode) throttle_suppressed = auto_throttle_mode; if (should_log(MASK_LOG_MODE)) - Log_Write_Mode(control_mode); + DataFlash.Log_Write_Mode(control_mode); // reset attitude integrators on mode change rollController.reset_I();