From 3c1f4b1ad7c4a4e62f37751f0e5aa7094ea11004 Mon Sep 17 00:00:00 2001 From: Jason Short Date: Sat, 10 Mar 2012 12:44:18 -0800 Subject: [PATCH] ACM: changed alt hold initialization of altitude to be immediate --- ArduCopter/system.pde | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/ArduCopter/system.pde b/ArduCopter/system.pde index ea32cdc2d1..5cd24dd1c1 100644 --- a/ArduCopter/system.pde +++ b/ArduCopter/system.pde @@ -447,7 +447,7 @@ static void set_mode(byte mode) roll_pitch_mode = ALT_HOLD_RP; throttle_mode = ALT_HOLD_THR; - set_next_WP(¤t_loc); + force_new_altitude(max(current_loc.alt, 100)); break; case AUTO: