mirror of https://github.com/ArduPilot/ardupilot
Rover: call periodic fence update function
This commit is contained in:
parent
6891225438
commit
b6bc0c638c
|
@ -59,6 +59,7 @@ const AP_Scheduler::Task Rover::scheduler_tasks[] = {
|
||||||
#if VISUAL_ODOMETRY_ENABLED == ENABLED
|
#if VISUAL_ODOMETRY_ENABLED == ENABLED
|
||||||
SCHED_TASK_CLASS(AP_VisualOdom, &rover.g2.visual_odom, update, 50, 200),
|
SCHED_TASK_CLASS(AP_VisualOdom, &rover.g2.visual_odom, update, 50, 200),
|
||||||
#endif
|
#endif
|
||||||
|
SCHED_TASK_CLASS(AC_Fence, &rover.g2.fence, update, 10, 100),
|
||||||
SCHED_TASK(update_wheel_encoder, 50, 200),
|
SCHED_TASK(update_wheel_encoder, 50, 200),
|
||||||
SCHED_TASK(update_compass, 10, 200),
|
SCHED_TASK(update_compass, 10, 200),
|
||||||
SCHED_TASK(update_mission, 50, 200),
|
SCHED_TASK(update_mission, 50, 200),
|
||||||
|
|
Loading…
Reference in New Issue