From e34702f5245c87e7d7ef138ddd2ee0b3fb07b0fc Mon Sep 17 00:00:00 2001
From: Randy Mackay <rmackay9@yahoo.com>
Date: Mon, 15 Jul 2013 20:44:18 +0900
Subject: [PATCH] Copter: bug fix for descent during loiter_turns

---
 ArduCopter/navigation.pde | 1 +
 1 file changed, 1 insertion(+)

diff --git a/ArduCopter/navigation.pde b/ArduCopter/navigation.pde
index 7a984bc8e..19ee14b13 100644
--- a/ArduCopter/navigation.pde
+++ b/ArduCopter/navigation.pde
@@ -287,6 +287,7 @@ update_circle(float dt)
         // calculate target position
         circle_target.x = circle_center.x + cir_radius * cosf(-circle_angle);
         circle_target.y = circle_center.y - cir_radius * sinf(-circle_angle);
+        circle_target.z = wp_nav.get_desired_alt();
 
         // re-use loiter position controller
         wp_nav.set_loiter_target(circle_target);
-- 
GitLab