ArduSub: remove Baro accumulate API

no backend actually needs to be prodded, everything is done on timers
This commit is contained in:
Peter Barker 2024-04-17 23:21:16 +10:00 committed by Peter Barker
parent e47c65f010
commit cccd105ac9
1 changed files with 0 additions and 1 deletions

View File

@ -79,7 +79,6 @@ const AP_Scheduler::Task Sub::scheduler_tasks[] = {
SCHED_TASK(update_altitude, 10, 100, 18), SCHED_TASK(update_altitude, 10, 100, 18),
SCHED_TASK(three_hz_loop, 3, 75, 21), SCHED_TASK(three_hz_loop, 3, 75, 21),
SCHED_TASK(update_turn_counter, 10, 50, 24), SCHED_TASK(update_turn_counter, 10, 50, 24),
SCHED_TASK_CLASS(AP_Baro, &sub.barometer, accumulate, 50, 90, 27),
SCHED_TASK(one_hz_loop, 1, 100, 33), SCHED_TASK(one_hz_loop, 1, 100, 33),
SCHED_TASK_CLASS(GCS, (GCS*)&sub._gcs, update_receive, 400, 180, 36), SCHED_TASK_CLASS(GCS, (GCS*)&sub._gcs, update_receive, 400, 180, 36),
SCHED_TASK_CLASS(GCS, (GCS*)&sub._gcs, update_send, 400, 550, 39), SCHED_TASK_CLASS(GCS, (GCS*)&sub._gcs, update_send, 400, 550, 39),