Skip to content
Snippets Groups Projects
Commit 7649907e authored by Andrew Tridgell's avatar Andrew Tridgell
Browse files

Plane: run terrain.update() more often

this provides faster checking of mission waypoints
parent eeb04ba1
No related branches found
No related tags found
No related merge requests found
......@@ -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
*/
......
0% Loading or .
You are about to add 0 people to the discussion. Proceed with caution.
Finish editing this message first!
Please register or to comment