Browse Source

Copter: call periodic fence update function

mission-4.1.18
Peter Barker 5 years ago committed by Randy Mackay
parent
commit
4d6dc9b0a7
  1. 3
      ArduCopter/Copter.cpp

3
ArduCopter/Copter.cpp

@ -127,6 +127,9 @@ const AP_Scheduler::Task Copter::scheduler_tasks[] = { @@ -127,6 +127,9 @@ const AP_Scheduler::Task Copter::scheduler_tasks[] = {
SCHED_TASK(three_hz_loop, 3, 75),
SCHED_TASK_CLASS(AP_ServoRelayEvents, &copter.ServoRelayEvents, update_events, 50, 75),
SCHED_TASK_CLASS(AP_Baro, &copter.barometer, accumulate, 50, 90),
#if AC_FENCE == ENABLED
SCHED_TASK_CLASS(AC_Fence, &copter.fence, update, 10, 100),
#endif
#if PRECISION_LANDING == ENABLED
SCHED_TASK(update_precland, 400, 50),
#endif

Loading…
Cancel
Save