diff --git a/ArduPlane/ArduPlane.pde b/ArduPlane/ArduPlane.pde
index 02d5b2def85db046a88fff12fcb525914facedc5..654aa9feefd0e51a43d810ef62b9510982afa732 100644
--- a/ArduPlane/ArduPlane.pde
+++ b/ArduPlane/ArduPlane.pde
@@ -796,7 +796,7 @@ static const AP_Scheduler::Task scheduler_tasks[] PROGMEM = {
 #if FRSKY_TELEM_ENABLED == ENABLED
     { telemetry_send,        10,    100 },	
 #endif
-
+    { terrain_update,         5,    500 },
 };
 
 // setup the var_info table
@@ -1023,7 +1023,6 @@ static void one_second_loop()
     AP_Notify::flags.armed = arming.is_armed() || arming.arming_required() == AP_Arming::NO;
 
 #if AP_TERRAIN_AVAILABLE
-    terrain.update();
     if (should_log(MASK_LOG_GPS)) {
         terrain.log_terrain_data(DataFlash);
     }
@@ -1048,6 +1047,13 @@ static void compass_save()
     }
 }
 
+static void terrain_update(void)
+{
+#if AP_TERRAIN_AVAILABLE
+    terrain.update();
+#endif
+}
+
 /*
   once a second update the airspeed calibration ratio
  */