Plane: Option to trig by distance only when in AUTO mode

This commit is contained in:
André Kjellstrup 2017-10-24 12:45:09 +02:00 committed by Francisco Ferreira
parent e7a1ceca4c
commit 1d27e21d83

View File

@ -295,6 +295,9 @@ 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