Skip to content
New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

Fast Copter Fences #25698

Merged
merged 1 commit into from
Feb 28, 2024
Merged
Changes from all commits
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
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),
Copy link
Contributor

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

might be worth moving fence checking to an IO callback, or add a FENCE_OPTIONS bit for fast fence checking

#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
Loading