mirror of https://github.com/ArduPilot/ardupilot
Copter:Scheduler - increase update rate for rpm to 40Hz for helicopter governor
This commit is contained in:
parent
e9552ec4e1
commit
8312dcae5d
|
@ -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_InertialSensor, &copter.ins, periodic, 400, 50),
|
||||||
SCHED_TASK_CLASS(AP_Scheduler, &copter.scheduler, update_logging, 0.1, 75),
|
SCHED_TASK_CLASS(AP_Scheduler, &copter.scheduler, update_logging, 0.1, 75),
|
||||||
#if RPM_ENABLED == ENABLED
|
#if RPM_ENABLED == ENABLED
|
||||||
SCHED_TASK(rpm_update, 10, 200),
|
SCHED_TASK(rpm_update, 40, 200),
|
||||||
#endif
|
#endif
|
||||||
SCHED_TASK(compass_cal_update, 100, 100),
|
SCHED_TASK(compass_cal_update, 100, 100),
|
||||||
SCHED_TASK(accel_cal_update, 10, 100),
|
SCHED_TASK(accel_cal_update, 10, 100),
|
||||||
|
|
Loading…
Reference in New Issue