From 7649907ec2d44ad34baefc0438f9166580fe197f Mon Sep 17 00:00:00 2001 From: Andrew Tridgell Date: Mon, 25 Aug 2014 14:55:40 +1000 Subject: [PATCH] Plane: run terrain.update() more often this provides faster checking of mission waypoints --- ArduPlane/ArduPlane.pde | 10 ++++++++-- 1 file changed, 8 insertions(+), 2 deletions(-) diff --git a/ArduPlane/ArduPlane.pde b/ArduPlane/ArduPlane.pde index 02d5b2def8..654aa9feef 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 */