mirror of https://github.com/ArduPilot/ardupilot
Clears Auto_land timer
This commit is contained in:
parent
ce83b8efa5
commit
9d9bef37a8
|
@ -455,6 +455,9 @@ static void set_mode(byte mode)
|
||||||
// clearing value used in interactive alt hold
|
// clearing value used in interactive alt hold
|
||||||
manual_boost = 0;
|
manual_boost = 0;
|
||||||
|
|
||||||
|
// do not auto_land if we are leaving RTL
|
||||||
|
auto_land_timer = 0;
|
||||||
|
|
||||||
Serial.println(flight_mode_strings[control_mode]);
|
Serial.println(flight_mode_strings[control_mode]);
|
||||||
|
|
||||||
// report the GPS and Motor arming status
|
// report the GPS and Motor arming status
|
||||||
|
|
Loading…
Reference in New Issue