Copter: fix update_thr_average to run at 100hz

Committed by Randy on Julien's behalf
This commit is contained in:
Julien Dubois 2015-04-28 22:41:24 +09:00 committed by Randy Mackay
parent 56a8bf5460
commit b7a6e3bf2c

View File

@ -730,7 +730,7 @@ static const AP_Scheduler::Task scheduler_tasks[] PROGMEM = {
{ auto_trim, 40, 14 },
{ update_altitude, 40, 100 },
{ run_nav_updates, 8, 80 },
{ update_thr_average, 40, 10 },
{ update_thr_average, 4, 10 },
{ three_hz_loop, 133, 9 },
{ compass_accumulate, 8, 42 },
{ barometer_accumulate, 8, 25 },