mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-09 09:28:31 -04:00
ArduSub: Fix build with RPM_ENABLED
This commit is contained in:
parent
b80393b2cd
commit
132baa1ad0
@ -76,7 +76,7 @@ const AP_Scheduler::Task Sub::scheduler_tasks[] = {
|
|||||||
SCHED_TASK_CLASS(AP_InertialSensor, &sub.ins, periodic, 400, 50, 60),
|
SCHED_TASK_CLASS(AP_InertialSensor, &sub.ins, periodic, 400, 50, 60),
|
||||||
SCHED_TASK_CLASS(AP_Scheduler, &sub.scheduler, update_logging, 0.1, 75, 63),
|
SCHED_TASK_CLASS(AP_Scheduler, &sub.scheduler, update_logging, 0.1, 75, 63),
|
||||||
#if RPM_ENABLED == ENABLED
|
#if RPM_ENABLED == ENABLED
|
||||||
SCHED_TASK_CLASS(AP_RPM, &sub.rpm_sensor, update 10, 200, 66),
|
SCHED_TASK_CLASS(AP_RPM, &sub.rpm_sensor, update, 10, 200, 66),
|
||||||
#endif
|
#endif
|
||||||
SCHED_TASK_CLASS(Compass, &sub.compass, cal_update, 100, 100, 69),
|
SCHED_TASK_CLASS(Compass, &sub.compass, cal_update, 100, 100, 69),
|
||||||
SCHED_TASK(terrain_update, 10, 100, 72),
|
SCHED_TASK(terrain_update, 10, 100, 72),
|
||||||
|
Loading…
Reference in New Issue
Block a user