diff --git a/ArduPlane/system.cpp b/ArduPlane/system.cpp index ad2fd78326..cfdd28aab3 100644 --- a/ArduPlane/system.cpp +++ b/ArduPlane/system.cpp @@ -295,7 +295,10 @@ void Plane::set_mode(enum FlightMode mode, mode_reason_t reason) #if FRSKY_TELEM_ENABLED == ENABLED frsky_telemetry.update_control_mode(control_mode); #endif - +#if CAMERA == ENABLED + camera.set_is_auto_mode(control_mode == AUTO); +#endif + if (previous_mode == AUTOTUNE && control_mode != AUTOTUNE) { // restore last gains autotune_restore();