mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-03 06:28:27 -04:00
Tracker: call compass cal routine directly from sched table
This commit is contained in:
parent
47d9960eb9
commit
09a11429e1
@ -49,7 +49,7 @@ const AP_Scheduler::Task Tracker::scheduler_tasks[] = {
|
||||
SCHED_TASK_CLASS(AP_InertialSensor, &tracker.ins, periodic, 50, 50),
|
||||
SCHED_TASK_CLASS(AP_Notify, &tracker.notify, update, 50, 100),
|
||||
SCHED_TASK(one_second_loop, 1, 3900),
|
||||
SCHED_TASK(compass_cal_update, 50, 100),
|
||||
SCHED_TASK_CLASS(Compass, &tracker.compass, cal_update, 50, 100),
|
||||
SCHED_TASK(accel_cal_update, 10, 100)
|
||||
};
|
||||
|
||||
|
@ -247,7 +247,6 @@ private:
|
||||
void compass_save();
|
||||
void init_compass_location();
|
||||
void update_compass(void);
|
||||
void compass_cal_update();
|
||||
void accel_cal_update(void);
|
||||
void update_GPS(void);
|
||||
void handle_battery_failsafe(const char* type_str, const int8_t action);
|
||||
|
@ -36,15 +36,6 @@ void Tracker::update_compass(void)
|
||||
}
|
||||
}
|
||||
|
||||
/*
|
||||
calibrate compass
|
||||
*/
|
||||
void Tracker::compass_cal_update() {
|
||||
if (!hal.util->get_soft_armed()) {
|
||||
compass.compass_cal_update();
|
||||
}
|
||||
}
|
||||
|
||||
// Save compass offsets
|
||||
void Tracker::compass_save() {
|
||||
if (AP::compass().enabled() &&
|
||||
|
Loading…
Reference in New Issue
Block a user