diff --git a/ArduCopter/control_loiter.pde b/ArduCopter/control_loiter.pde
index d0b7d212d5..671fa7e7d3 100644
--- a/ArduCopter/control_loiter.pde
+++ b/ArduCopter/control_loiter.pde
@@ -33,7 +33,7 @@ static void loiter_run()
     float target_climb_rate = 0;
 
     // if not auto armed set throttle to zero and exit immediately
-    if(!ap.auto_armed || !inertial_nav.get_filter_status().flags.horiz_pos_abs) {
+    if(!ap.auto_armed || !ap.home_is_set) {
         wp_nav.init_loiter_target();
         attitude_control.relax_bf_rate_controller();
         attitude_control.set_yaw_target_to_current_heading();
diff --git a/ArduCopter/control_poshold.pde b/ArduCopter/control_poshold.pde
index e7e5a40435..11695c6080 100644
--- a/ArduCopter/control_poshold.pde
+++ b/ArduCopter/control_poshold.pde
@@ -154,7 +154,7 @@ static void poshold_run()
     const Vector3f& vel = inertial_nav.get_velocity();
 
     // if not auto armed set throttle to zero and exit immediately
-    if(!ap.auto_armed || !inertial_nav.get_filter_status().flags.horiz_pos_abs) {
+    if(!ap.auto_armed || !ap.home_is_set) {
         wp_nav.init_loiter_target();
         attitude_control.relax_bf_rate_controller();
         attitude_control.set_yaw_target_to_current_heading();
diff --git a/ArduCopter/control_rtl.pde b/ArduCopter/control_rtl.pde
index 6032f0d5a9..598a9c06bf 100644
--- a/ArduCopter/control_rtl.pde
+++ b/ArduCopter/control_rtl.pde
@@ -261,7 +261,7 @@ static void rtl_descent_run()
     float target_yaw_rate = 0;
 
     // if not auto armed set throttle to zero and exit immediately
-    if(!ap.auto_armed || !inertial_nav.get_filter_status().flags.horiz_pos_abs) {
+    if(!ap.auto_armed || !ap.home_is_set) {
         attitude_control.relax_bf_rate_controller();
         attitude_control.set_yaw_target_to_current_heading();
         attitude_control.set_throttle_out(0, false);