From 336441b109a123e93ac1357367ce6816fc11afd0 Mon Sep 17 00:00:00 2001 From: Jason Short Date: Sun, 19 Feb 2012 13:13:42 -0800 Subject: [PATCH] reset slow_WP option at mode switch --- ArduCopter/system.pde | 3 +++ 1 file changed, 3 insertions(+) diff --git a/ArduCopter/system.pde b/ArduCopter/system.pde index e6637a1fe0..5f1f2593e7 100644 --- a/ArduCopter/system.pde +++ b/ArduCopter/system.pde @@ -419,6 +419,9 @@ static void set_mode(byte mode) // clearing value used to force the copter down in landing mode 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 auto_land_timer = 0;