From 7e3233f8e83d94c0d7cf1825f5c72b120866ea1e Mon Sep 17 00:00:00 2001 From: Peter Barker Date: Sun, 1 Jan 2023 11:27:30 +1100 Subject: [PATCH] ArduSub: remove logging of first home location into CMD message set --- ArduSub/commands.cpp | 14 -------------- 1 file changed, 14 deletions(-) diff --git a/ArduSub/commands.cpp b/ArduSub/commands.cpp index dd37d06e24..7009f8cd21 100644 --- a/ArduSub/commands.cpp +++ b/ArduSub/commands.cpp @@ -51,7 +51,6 @@ bool Sub::set_home_to_current_location(bool lock) } // set_home - sets ahrs home (used for RTL) to specified location -// initialises inertial nav and compass on first call // returns true if home location set successfully bool Sub::set_home(const Location& loc, bool lock) { @@ -61,24 +60,11 @@ bool Sub::set_home(const Location& loc, bool lock) return false; } - const bool home_was_set = ahrs.home_is_set(); - // set ahrs home (used for RTL) if (!ahrs.set_home(loc)) { return false; } - // init inav and compass declination - if (!home_was_set) { - // log new home position which mission library will pull from ahrs - if (should_log(MASK_LOG_CMD)) { - AP_Mission::Mission_Command temp_cmd; - if (mission.read_cmd_from_storage(0, temp_cmd)) { - logger.Write_Mission_Cmd(mission, temp_cmd); - } - } - } - // lock home position if (lock) { ahrs.lock_home();