diff --git a/ArduCopter/mode.cpp b/ArduCopter/mode.cpp index 09e82f8c62..112d475feb 100644 --- a/ArduCopter/mode.cpp +++ b/ArduCopter/mode.cpp @@ -300,7 +300,7 @@ bool Copter::set_mode(const uint8_t new_mode, const ModeReason reason) return false; } #endif - return copter.set_mode(static_cast(new_mode), ModeReason::GCS_COMMAND); + return copter.set_mode(static_cast(new_mode), reason); } // update_flight_mode - calls the appropriate attitude controllers based on flight mode