Browse Source

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

mission-4.1.18
André Kjellstrup 7 years ago committed by Francisco Ferreira
parent
commit
e7a1ceca4c
  1. 3
      ArduCopter/flight_mode.cpp

3
ArduCopter/flight_mode.cpp

@ -155,6 +155,9 @@ failed: @@ -155,6 +155,9 @@ failed:
#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
} else {
// Log error that we failed to enter desired flight mode

Loading…
Cancel
Save