mirror of https://github.com/ArduPilot/ardupilot
reset slow_WP option at mode switch
This commit is contained in:
parent
151e710668
commit
434b059586
|
@ -419,6 +419,9 @@ static void set_mode(byte mode)
|
||||||
// clearing value used to force the copter down in landing mode
|
// clearing value used to force the copter down in landing mode
|
||||||
landing_boost = 0;
|
landing_boost = 0;
|
||||||
|
|
||||||
|
// do we want to come to a stop or pass a WP?
|
||||||
|
slow_wp = false;
|
||||||
|
|
||||||
// do not auto_land if we are leaving RTL
|
// do not auto_land if we are leaving RTL
|
||||||
auto_land_timer = 0;
|
auto_land_timer = 0;
|
||||||
|
|
||||||
|
|
Loading…
Reference in New Issue