From 8312dcae5d538ab4c48e4d30dac60a51095c1404 Mon Sep 17 00:00:00 2001 From: ChristopherOlson Date: Sat, 24 Nov 2018 20:49:06 -0600 Subject: [PATCH] Copter:Scheduler - increase update rate for rpm to 40Hz for helicopter governor --- ArduCopter/ArduCopter.cpp | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/ArduCopter/ArduCopter.cpp b/ArduCopter/ArduCopter.cpp index ef78384c53..df58c8ae58 100644 --- a/ArduCopter/ArduCopter.cpp +++ b/ArduCopter/ArduCopter.cpp @@ -151,7 +151,7 @@ const AP_Scheduler::Task Copter::scheduler_tasks[] = { SCHED_TASK_CLASS(AP_InertialSensor, &copter.ins, periodic, 400, 50), SCHED_TASK_CLASS(AP_Scheduler, &copter.scheduler, update_logging, 0.1, 75), #if RPM_ENABLED == ENABLED - SCHED_TASK(rpm_update, 10, 200), + SCHED_TASK(rpm_update, 40, 200), #endif SCHED_TASK(compass_cal_update, 100, 100), SCHED_TASK(accel_cal_update, 10, 100),