Copter: run compass_accumulate at 100hz

This commit is contained in:
Jonathan Challinger 2015-02-25 19:14:15 -08:00 committed by Andrew Tridgell
parent 5fe6db0dc9
commit ee1209c03f
1 changed files with 2 additions and 1 deletions

View File

@ -113,7 +113,7 @@ const AP_Scheduler::Task Copter::scheduler_tasks[] PROGMEM = {
SCHED_TASK(run_nav_updates, 8, 100),
SCHED_TASK(update_thr_average, 4, 90),
SCHED_TASK(three_hz_loop, 133, 75),
SCHED_TASK(compass_accumulate, 8, 100),
SCHED_TASK(compass_accumulate, 4, 100),
SCHED_TASK(barometer_accumulate, 8, 90),
#if PRECISION_LANDING == ENABLED
SCHED_TASK(update_precland, 8, 50),
@ -138,6 +138,7 @@ const AP_Scheduler::Task Copter::scheduler_tasks[] PROGMEM = {
SCHED_TASK(perf_update, 4000, 75),
SCHED_TASK(read_receiver_rssi, 40, 75),
SCHED_TASK(rpm_update, 40, 200),
SCHED_TASK(compass_cal_update, 4, 100),
#if FRSKY_TELEM_ENABLED == ENABLED
SCHED_TASK(frsky_telemetry_send, 80, 75),
#endif