From f53892a1fa6a250ed1a48280639c1c8f9dc796d7 Mon Sep 17 00:00:00 2001 From: Pierre Kancir Date: Thu, 31 Dec 2020 09:41:00 +0100 Subject: [PATCH] Copter: don't report initial mode switch as failsafe mode change --- ArduCopter/system.cpp | 6 ++---- 1 file changed, 2 insertions(+), 4 deletions(-) diff --git a/ArduCopter/system.cpp b/ArduCopter/system.cpp index 0bea87f0be..abf845aff1 100644 --- a/ArduCopter/system.cpp +++ b/ArduCopter/system.cpp @@ -216,13 +216,11 @@ void Copter::init_ardupilot() enable_motor_output(); } - // attempt to switch to RTL, if this fails then switch to Land + // attempt to set the intial_mode, else set to STABILIZE if (!set_mode((enum Mode::Number)g.initial_mode.get(), ModeReason::INITIALISED)) { // set mode to STABILIZE will trigger mode change notification to pilot set_mode(Mode::Number::STABILIZE, ModeReason::UNAVAILABLE); - } else { - // alert pilot to mode change - AP_Notify::events.failsafe_mode_change = 1; + AP_Notify::events.user_mode_change_failed = 1; } // flag that initialisation has completed