From ee1209c03f39e1516b727521fac71cd5aa8b892e Mon Sep 17 00:00:00 2001 From: Jonathan Challinger Date: Wed, 25 Feb 2015 19:14:15 -0800 Subject: [PATCH] Copter: run compass_accumulate at 100hz --- ArduCopter/ArduCopter.cpp | 3 ++- 1 file changed, 2 insertions(+), 1 deletion(-) diff --git a/ArduCopter/ArduCopter.cpp b/ArduCopter/ArduCopter.cpp index bebb9a392c..4cf6a614f3 100644 --- a/ArduCopter/ArduCopter.cpp +++ b/ArduCopter/ArduCopter.cpp @@ -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