From 6e94b21d6733a739ec02399228310aa183c5f466 Mon Sep 17 00:00:00 2001 From: Jason Short Date: Mon, 16 Jan 2012 14:28:23 -0800 Subject: [PATCH] Altitude no longer resets when moving loiter WP --- ArduCopter/ArduCopter.pde | 3 ++- 1 file changed, 2 insertions(+), 1 deletion(-) diff --git a/ArduCopter/ArduCopter.pde b/ArduCopter/ArduCopter.pde index 782820f951..bf0042875e 100644 --- a/ArduCopter/ArduCopter.pde +++ b/ArduCopter/ArduCopter.pde @@ -1689,7 +1689,8 @@ static void update_navigation() wp_control = NO_NAV_MODE; // reset LOITER to current position - next_WP = current_loc; + next_WP.lat = current_loc.lat; + next_WP.lng = current_loc.lng; }else{ // this is also set by GPS in update_nav