Browse Source

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

master
André Kjellstrup 7 years ago committed by Francisco Ferreira
parent
commit
1d27e21d83
  1. 5
      ArduPlane/system.cpp

5
ArduPlane/system.cpp

@ -295,7 +295,10 @@ void Plane::set_mode(enum FlightMode mode, mode_reason_t reason) @@ -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();

Loading…
Cancel
Save