From 18e566ccc58444f94dbcb6c6948b68a234bc9bd3 Mon Sep 17 00:00:00 2001 From: Dr Gareth Owen Date: Sat, 1 Jun 2013 11:44:25 +0100 Subject: [PATCH] failsafe gps lost bug fix --- ArduCopter/events.pde | 10 +++++----- 1 file changed, 5 insertions(+), 5 deletions(-) diff --git a/ArduCopter/events.pde b/ArduCopter/events.pde index daaf8a524d..7a4aa60855 100644 --- a/ArduCopter/events.pde +++ b/ArduCopter/events.pde @@ -18,7 +18,7 @@ static void failsafe_radio_on_event() // if throttle is zero disarm motors if (g.rc_3.control_in == 0) { init_disarm_motors(); - }else if(ap.home_is_set == true && home_distance > wp_nav.get_waypoint_radius()) { + }else if(ap.home_is_set == true && g_gps->status() == GPS::GPS_OK_FIX_3D && home_distance > wp_nav.get_waypoint_radius()) { set_mode(RTL); }else{ // We have no GPS or are very close to home so we will land @@ -38,7 +38,7 @@ static void failsafe_radio_on_event() // if failsafe_throttle is 2 (i.e. FS_THR_ENABLED_CONTINUE_MISSION) no need to do anything break; default: - if(ap.home_is_set == true && home_distance > wp_nav.get_waypoint_radius()) { + if(ap.home_is_set == true && g_gps->status() == GPS::GPS_OK_FIX_3D && home_distance > wp_nav.get_waypoint_radius()) { set_mode(RTL); }else{ // We have no GPS or are very close to home so we will land @@ -77,7 +77,7 @@ static void low_battery_event(void) } break; case AUTO: - if(ap.home_is_set == true && home_distance > wp_nav.get_waypoint_radius()) { + if(ap.home_is_set == true && g_gps->status() == GPS::GPS_OK_FIX_3D && home_distance > wp_nav.get_waypoint_radius()) { set_mode(RTL); }else{ // We have no GPS or are very close to home so we will land @@ -190,7 +190,7 @@ static void failsafe_gcs_check() // if throttle is zero disarm motors if (g.rc_3.control_in == 0) { init_disarm_motors(); - }else if(ap.home_is_set == true && home_distance > wp_nav.get_waypoint_radius()) { + }else if(ap.home_is_set == true && g_gps->status() == GPS::GPS_OK_FIX_3D && home_distance > wp_nav.get_waypoint_radius()) { set_mode(RTL); }else{ // We have no GPS or are very close to home so we will land @@ -210,7 +210,7 @@ static void failsafe_gcs_check() // if failsafe_throttle is 2 (i.e. FS_THR_ENABLED_CONTINUE_MISSION) no need to do anything break; default: - if(ap.home_is_set == true && home_distance > wp_nav.get_waypoint_radius()) { + if(ap.home_is_set == true && g_gps->status() == GPS::GPS_OK_FIX_3D && home_distance > wp_nav.get_waypoint_radius()) { set_mode(RTL); }else{ // We have no GPS or are very close to home so we will land