mirror of https://github.com/ArduPilot/ardupilot
Bug fix: When adjusting altitude, RTL then land will fail unless this var is reset to false.
This commit is contained in:
parent
1b9f75c844
commit
71f80f3a77
|
@ -400,6 +400,7 @@ static void set_mode(byte mode)
|
|||
|
||||
// clearing value used to force the copter down in landing mode
|
||||
landing_boost = 0;
|
||||
reset_throttle_flag = false;
|
||||
|
||||
// do we want to come to a stop or pass a WP?
|
||||
slow_wp = false;
|
||||
|
|
Loading…
Reference in New Issue