mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-03 14:38:30 -04:00
Rover: Option to trig by distance only when in AUTO mode
This commit is contained in:
parent
1a63fd85d8
commit
aab22d7dad
@ -229,6 +229,9 @@ bool Rover::set_mode(Mode &new_mode, mode_reason_t reason)
|
|||||||
#if FRSKY_TELEM_ENABLED == ENABLED
|
#if FRSKY_TELEM_ENABLED == ENABLED
|
||||||
frsky_telemetry.update_control_mode(control_mode->mode_number());
|
frsky_telemetry.update_control_mode(control_mode->mode_number());
|
||||||
#endif
|
#endif
|
||||||
|
#if CAMERA == ENABLED
|
||||||
|
camera.set_is_auto_mode(control_mode->mode_number() == AUTO);
|
||||||
|
#endif
|
||||||
|
|
||||||
old_mode.exit();
|
old_mode.exit();
|
||||||
|
|
||||||
|
Loading…
Reference in New Issue
Block a user