mirror of https://github.com/ArduPilot/ardupilot
Rover: bugfix PRECISION_LANDING needing AP_GRIPPER_ENABLED
This commit is contained in:
parent
87e8c5e0ba
commit
456a87de95
|
@ -97,10 +97,10 @@ const AP_Scheduler::Task Rover::scheduler_tasks[] = {
|
||||||
SCHED_TASK_CLASS(AP_ServoRelayEvents, &rover.ServoRelayEvents, update_events, 50, 200, 66),
|
SCHED_TASK_CLASS(AP_ServoRelayEvents, &rover.ServoRelayEvents, update_events, 50, 200, 66),
|
||||||
#if AP_GRIPPER_ENABLED
|
#if AP_GRIPPER_ENABLED
|
||||||
SCHED_TASK_CLASS(AP_Gripper, &rover.g2.gripper, update, 10, 75, 69),
|
SCHED_TASK_CLASS(AP_Gripper, &rover.g2.gripper, update, 10, 75, 69),
|
||||||
|
#endif
|
||||||
#if PRECISION_LANDING == ENABLED
|
#if PRECISION_LANDING == ENABLED
|
||||||
SCHED_TASK(update_precland, 400, 50, 70),
|
SCHED_TASK(update_precland, 400, 50, 70),
|
||||||
#endif
|
#endif
|
||||||
#endif
|
|
||||||
#if AP_RPM_ENABLED
|
#if AP_RPM_ENABLED
|
||||||
SCHED_TASK_CLASS(AP_RPM, &rover.rpm_sensor, update, 10, 100, 72),
|
SCHED_TASK_CLASS(AP_RPM, &rover.rpm_sensor, update, 10, 100, 72),
|
||||||
#endif
|
#endif
|
||||||
|
|
Loading…
Reference in New Issue