Skip to content

Commit

Permalink
Copter: check fence at faster rates when going faster to avoid massiv…
Browse files Browse the repository at this point in the history
…e fence breaches
  • Loading branch information
andyp1per committed Feb 27, 2024
1 parent 079ffb4 commit 04e2877
Showing 1 changed file with 3 additions and 6 deletions.
9 changes: 3 additions & 6 deletions ArduCopter/Copter.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -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),
Expand Down Expand Up @@ -622,12 +625,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();

Expand Down

0 comments on commit 04e2877

Please sign in to comment.