Copter: check fence at faster rates when going faster to avoid massive fence breaches

This commit is contained in:
Andy Piper 2024-01-02 19:53:12 +00:00 committed by Peter Barker
parent 6ae7b3385f
commit 976288364b
1 changed files with 3 additions and 6 deletions

View File

@ -149,6 +149,9 @@ const AP_Scheduler::Task Copter::scheduler_tasks[] = {
SCHED_TASK(rc_loop, 250, 130, 3),
SCHED_TASK(throttle_loop, 50, 75, 6),
#if AP_FENCE_ENABLED
SCHED_TASK(fence_check, 25, 100, 7),
#endif
SCHED_TASK_CLASS(AP_GPS, &copter.gps, update, 50, 200, 9),
#if AP_OPTICALFLOW_ENABLED
SCHED_TASK_CLASS(AP_OpticalFlow, &copter.optflow, update, 200, 160, 12),
@ -628,12 +631,6 @@ void Copter::three_hz_loop()
// check for deadreckoning failsafe
failsafe_deadreckon_check();
#if AP_FENCE_ENABLED
// check if we have breached a fence
fence_check();
#endif // AP_FENCE_ENABLED
// update ch6 in flight tuning
tuning();