From d146d6aaa6ab0eccdf7e35ccef3057507732d867 Mon Sep 17 00:00:00 2001 From: Randy Mackay Date: Sun, 28 Apr 2013 17:15:13 +0900 Subject: [PATCH] Copter: restore update_altitude to run at 10hz --- ArduCopter/ArduCopter.pde | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/ArduCopter/ArduCopter.pde b/ArduCopter/ArduCopter.pde index 1316eba993..d85204ae48 100644 --- a/ArduCopter/ArduCopter.pde +++ b/ArduCopter/ArduCopter.pde @@ -848,7 +848,7 @@ static const AP_Scheduler::Task scheduler_tasks[] PROGMEM = { { update_GPS, 2, 900 }, { update_navigation, 10, 500 }, { medium_loop, 2, 700 }, - { update_altitude, 5, 1000 }, + { update_altitude, 10, 1000 }, { fifty_hz_loop, 2, 950 }, { run_nav_updates, 10, 800 }, { slow_loop, 10, 500 },