From 4b0495bb1584876632a08ba1812b8387b0ca9266 Mon Sep 17 00:00:00 2001 From: Peter Barker Date: Wed, 24 Jun 2015 12:13:24 +1000 Subject: [PATCH] Rover: use common mission logging code --- APMrover2/GCS_Mavlink.cpp | 4 ++-- APMrover2/Log.cpp | 24 +----------------------- APMrover2/Rover.h | 2 -- APMrover2/commands_logic.cpp | 2 +- 4 files changed, 4 insertions(+), 28 deletions(-) diff --git a/APMrover2/GCS_Mavlink.cpp b/APMrover2/GCS_Mavlink.cpp index ff1810d852..b6d7361226 100644 --- a/APMrover2/GCS_Mavlink.cpp +++ b/APMrover2/GCS_Mavlink.cpp @@ -1105,11 +1105,11 @@ void GCS_MAVLINK::handleMessage(mavlink_message_t* msg) break; } - // XXX receive a WP from GCS and store in EEPROM + // GCS has sent us a mission item, store to EEPROM case MAVLINK_MSG_ID_MISSION_ITEM: { if (handle_mission_item(msg, rover.mission)) { - rover.Log_Write_EntireMission(); + rover.DataFlash.Log_Write_EntireMission(rover.mission); } break; } diff --git a/APMrover2/Log.cpp b/APMrover2/Log.cpp index 5f091eb720..3ee6b3d1c8 100644 --- a/APMrover2/Log.cpp +++ b/APMrover2/Log.cpp @@ -189,14 +189,6 @@ void Rover::Log_Write_Performance() DataFlash.WriteBlock(&pkt, sizeof(pkt)); } -// Write a mission command. Total length : 36 bytes -void Rover::Log_Write_Cmd(const AP_Mission::Mission_Command &cmd) -{ - mavlink_mission_item_t mav_cmd = {}; - AP_Mission::mission_cmd_to_mavlink(cmd,mav_cmd); - DataFlash.Log_Write_MavCmd(mission.num_commands(),mav_cmd); -} - struct PACKED log_Steering { LOG_PACKET_HEADER; uint64_t time_us; @@ -235,19 +227,7 @@ void Rover::Log_Write_Startup(uint8_t type) // write all commands to the dataflash as well if (should_log(MASK_LOG_CMD)) { - Log_Write_EntireMission(); - } -} - -void Rover::Log_Write_EntireMission() -{ - DataFlash.Log_Write_Message_P(PSTR("New mission")); - - AP_Mission::Mission_Command cmd; - for (uint16_t i = 0; i < mission.num_commands(); i++) { - if (mission.read_cmd_from_storage(i,cmd)) { - Log_Write_Cmd(cmd); - } + DataFlash.Log_Write_EntireMission(mission); } } @@ -439,11 +419,9 @@ void Rover::start_logging() // dummy functions void Rover::Log_Write_Startup(uint8_t type) {} -void Rover::Log_Write_EntireMission() {} void Rover::Log_Write_Current() {} void Rover::Log_Write_Nav_Tuning() {} void Rover::Log_Write_Performance() {} -void Rover::Log_Write_Cmd(const AP_Mission::Mission_Command &cmd) {} int8_t Rover::process_logs(uint8_t argc, const Menu::arg *argv) { return 0; } void Rover::Log_Write_Control_Tuning() {} void Rover::Log_Write_Sonar() {} diff --git a/APMrover2/Rover.h b/APMrover2/Rover.h index 801f214c74..fbc3a8436e 100644 --- a/APMrover2/Rover.h +++ b/APMrover2/Rover.h @@ -398,7 +398,6 @@ private: void Log_Write_Performance(); void Log_Write_Steering(); void Log_Write_Startup(uint8_t type); - void Log_Write_EntireMission(); void Log_Write_Control_Tuning(); void Log_Write_Nav_Tuning(); void Log_Write_Sonar(); @@ -481,7 +480,6 @@ private: void frsky_telemetry_send(void); void print_hit_enter(); void gcs_send_text_fmt(const prog_char_t *fmt, ...); - void Log_Write_Cmd(const AP_Mission::Mission_Command &cmd); void print_mode(AP_HAL::BetterStream *port, uint8_t mode); bool start_command(const AP_Mission::Mission_Command& cmd); bool verify_command(const AP_Mission::Mission_Command& cmd); diff --git a/APMrover2/commands_logic.cpp b/APMrover2/commands_logic.cpp index 11c9a6b63c..51ac3ee25e 100644 --- a/APMrover2/commands_logic.cpp +++ b/APMrover2/commands_logic.cpp @@ -9,7 +9,7 @@ bool Rover::start_command(const AP_Mission::Mission_Command& cmd) { // log when new commands start if (should_log(MASK_LOG_CMD)) { - Log_Write_Cmd(cmd); + DataFlash.Log_Write_Mission_Cmd(mission, cmd); } // exit immediately if not in AUTO mode