From 287b6e03641fbf842d5a7bd0f06b6ee32496296e Mon Sep 17 00:00:00 2001 From: Peter Barker Date: Sun, 1 Jan 2023 11:27:30 +1100 Subject: [PATCH] ArduCopter: remove logging of first home location into CMD message set --- ArduCopter/commands.cpp | 16 ---------------- 1 file changed, 16 deletions(-) diff --git a/ArduCopter/commands.cpp b/ArduCopter/commands.cpp index b5f2171d77..e5c2f152d0 100644 --- a/ArduCopter/commands.cpp +++ b/ArduCopter/commands.cpp @@ -54,7 +54,6 @@ bool Copter::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 Copter::set_home(const Location& loc, bool lock) { @@ -69,26 +68,11 @@ bool Copter::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) { -#if MODE_AUTO_ENABLED == ENABLED - // log new home position which mission library will pull from ahrs - if (should_log(MASK_LOG_CMD)) { - AP_Mission::Mission_Command temp_cmd; - if (mode_auto.mission.read_cmd_from_storage(0, temp_cmd)) { - logger.Write_Mission_Cmd(mode_auto.mission, temp_cmd); - } - } -#endif - } - // lock home position if (lock) { ahrs.lock_home();