AntennaTracker: remove vestiges of LearnType::LEARN_INTERNAL

57a3bc1397 changed the code from "internal" to "in-flight

It seems the old value of "1" was no longer valid

It also changed things to that the learning system saved the offsets.
This commit is contained in:
Peter Barker 2025-01-27 20:20:01 +11:00 committed by Andrew Tridgell
parent 9e4a180878
commit adf9fca840
3 changed files with 0 additions and 11 deletions

View File

@ -53,7 +53,6 @@ const AP_Scheduler::Task Tracker::scheduler_tasks[] = {
SCHED_TASK(update_tracking, 50, 1000, 15),
SCHED_TASK(update_GPS, 10, 4000, 20),
SCHED_TASK(update_compass, 10, 1500, 25),
SCHED_TASK(compass_save, 0.02, 200, 30),
SCHED_TASK_CLASS(AP_BattMonitor, &tracker.battery, read, 10, 1500, 35),
SCHED_TASK_CLASS(AP_Baro, &tracker.barometer, update, 10, 1500, 40),
SCHED_TASK_CLASS(GCS, (GCS*)&tracker._gcs, update_receive, 50, 1700, 45),

View File

@ -177,7 +177,6 @@ private:
// sensors.cpp
void update_ahrs();
void compass_save();
void update_compass(void);
void update_GPS(void);
void handle_battery_failsafe(const char* type_str, const int8_t action);

View File

@ -16,15 +16,6 @@ void Tracker::update_compass(void)
compass.read();
}
// Save compass offsets
void Tracker::compass_save() {
if (AP::compass().available() &&
compass.get_learn_type() >= Compass::LEARN_INTERNAL &&
!hal.util->get_soft_armed()) {
compass.save_offsets();
}
}
/*
read the GPS
*/