From 77958f8fd46785ca4633b1eacb52a242105387d8 Mon Sep 17 00:00:00 2001
From: Andrew Tridgell <tridge@samba.org>
Date: Tue, 25 Nov 2014 10:39:29 +1100
Subject: [PATCH] Plane: fixed CONTINUE_AND_CHANGE_ALT command

current_loc should be used, not prev_WP_loc
---
 ArduPlane/commands_logic.pde | 4 ++--
 1 file changed, 2 insertions(+), 2 deletions(-)

diff --git a/ArduPlane/commands_logic.pde b/ArduPlane/commands_logic.pde
index 3d72c711b..fefb87577 100644
--- a/ArduPlane/commands_logic.pde
+++ b/ArduPlane/commands_logic.pde
@@ -514,8 +514,8 @@ static bool verify_continue_and_change_alt()
         return true;
     }
    
-    //Is the next_WP less than 200 m away?
-    if (get_distance(prev_WP_loc, next_WP_loc) < 200.f) {
+    // Is the next_WP less than 200 m away?
+    if (get_distance(current_loc, next_WP_loc) < 200.f) {
         //push another 300 m down the line
         int32_t next_wp_bearing_cd = get_bearing_cd(prev_WP_loc, next_WP_loc);
         location_update(next_WP_loc, next_wp_bearing_cd * 0.01f, 300.f);
-- 
GitLab