diff --git a/ArduSub/Sub.h b/ArduSub/Sub.h index 9223865cb9..aff5c25620 100644 --- a/ArduSub/Sub.h +++ b/ArduSub/Sub.h @@ -216,7 +216,6 @@ private: control_mode_t control_mode; control_mode_t prev_control_mode; - ModeReason prev_control_mode_reason = ModeReason::UNKNOWN; #if RCMAP_ENABLED == ENABLED RCMapper rcmap; diff --git a/ArduSub/flight_mode.cpp b/ArduSub/flight_mode.cpp index 2fed178399..2801d2cad8 100644 --- a/ArduSub/flight_mode.cpp +++ b/ArduSub/flight_mode.cpp @@ -10,7 +10,6 @@ bool Sub::set_mode(control_mode_t mode, ModeReason reason) // return immediately if we are already in the desired mode if (mode == control_mode) { prev_control_mode = control_mode; - prev_control_mode_reason = control_mode_reason; control_mode_reason = reason; return true; @@ -70,7 +69,6 @@ bool Sub::set_mode(control_mode_t mode, ModeReason reason) exit_mode(control_mode, mode); prev_control_mode = control_mode; - prev_control_mode_reason = control_mode_reason; control_mode = mode; control_mode_reason = reason;