mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-02-02 05:58:30 -04:00
Plane: remove compass accumulate
This commit is contained in:
parent
346e9e36db
commit
903d00c4b2
@ -53,7 +53,6 @@ const AP_Scheduler::Task Plane::scheduler_tasks[] = {
|
||||
SCHED_TASK(gcs_data_stream_send, 50, 500),
|
||||
SCHED_TASK(update_events, 50, 150),
|
||||
SCHED_TASK_CLASS(AP_BattMonitor, &plane.battery, read, 10, 300),
|
||||
SCHED_TASK(compass_accumulate, 50, 200),
|
||||
SCHED_TASK_CLASS(AP_Baro, &plane.barometer, accumulate, 50, 150),
|
||||
SCHED_TASK(update_notify, 50, 300),
|
||||
SCHED_TASK(read_rangefinder, 50, 100),
|
||||
@ -192,16 +191,6 @@ void Plane::update_compass(void)
|
||||
}
|
||||
}
|
||||
|
||||
/*
|
||||
if the compass is enabled then try to accumulate a reading
|
||||
*/
|
||||
void Plane::compass_accumulate(void)
|
||||
{
|
||||
if (g.compass_enabled) {
|
||||
compass.accumulate();
|
||||
}
|
||||
}
|
||||
|
||||
/*
|
||||
do 10Hz logging
|
||||
*/
|
||||
|
@ -942,7 +942,6 @@ private:
|
||||
void update_compass(void);
|
||||
void update_alt(void);
|
||||
void afs_fs_check(void);
|
||||
void compass_accumulate(void);
|
||||
void compass_cal_update();
|
||||
void update_optical_flow(void);
|
||||
void one_second_loop(void);
|
||||
|
Loading…
Reference in New Issue
Block a user