From 40b7000cfdc80f5d2bdfd29eb0c8e0bce27239c4 Mon Sep 17 00:00:00 2001 From: Olivier-ADLER <olivier-git@nerim.net> Date: Sat, 15 Jun 2013 23:48:01 +0200 Subject: [PATCH] Copter: SuperSimple mode bug SuperSimple bearing was updated without checking for GPS 3D Fix availability. --- ArduCopter/navigation.pde | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/ArduCopter/navigation.pde b/ArduCopter/navigation.pde index f7b89263e..7aa230bdc 100644 --- a/ArduCopter/navigation.pde +++ b/ArduCopter/navigation.pde @@ -68,7 +68,7 @@ static void calc_distance_and_bearing() } // calculate home distance and bearing - if( ap.home_is_set ) { + if( ap.home_is_set && g_gps->status() == GPS::GPS_OK_FIX_3D ) { home_distance = pythagorous2(curr.x, curr.y); home_bearing = pv_get_bearing_cd(curr,Vector3f(0,0,0)); -- GitLab