From 29d6085babbeda9fd1e4ebadbbf0e5d5733b9998 Mon Sep 17 00:00:00 2001 From: Jason Short Date: Sat, 10 Mar 2012 12:37:54 -0800 Subject: [PATCH] added Force_new_altitude call for alt hold --- ArduCopter/ArduCopter.pde | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/ArduCopter/ArduCopter.pde b/ArduCopter/ArduCopter.pde index 64b458c31d..e71219448e 100644 --- a/ArduCopter/ArduCopter.pde +++ b/ArduCopter/ArduCopter.pde @@ -1658,7 +1658,7 @@ void update_throttle_mode(void) // we are under automatic throttle control // --------------------------------------- if(reset_throttle_flag) { - set_new_altitude(max(current_loc.alt, 100)); + force_new_altitude(max(current_loc.alt, 100)); reset_throttle_flag = false; update_throttle_cruise(); }