mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-03 06:28:27 -04:00
Sub: call compass cal routine directly from sched table
This commit is contained in:
parent
ad16f31e11
commit
c6a9130d84
@ -55,7 +55,7 @@ const AP_Scheduler::Task Sub::scheduler_tasks[] = {
|
||||
#if RPM_ENABLED == ENABLED
|
||||
SCHED_TASK(rpm_update, 10, 200),
|
||||
#endif
|
||||
SCHED_TASK(compass_cal_update, 100, 100),
|
||||
SCHED_TASK_CLASS(Compass, &sub.compass, cal_update, 100, 100),
|
||||
SCHED_TASK(accel_cal_update, 10, 100),
|
||||
SCHED_TASK(terrain_update, 10, 100),
|
||||
#if GRIPPER_ENABLED == ENABLED
|
||||
|
@ -455,7 +455,6 @@ private:
|
||||
static const struct LogStructure log_structure[];
|
||||
|
||||
void init_compass_location();
|
||||
void compass_cal_update(void);
|
||||
void fast_loop();
|
||||
void fifty_hz_loop();
|
||||
void update_batt_compass(void);
|
||||
|
@ -104,13 +104,6 @@ void Sub::init_optflow()
|
||||
}
|
||||
#endif // OPTFLOW == ENABLED
|
||||
|
||||
void Sub::compass_cal_update()
|
||||
{
|
||||
if (!hal.util->get_soft_armed()) {
|
||||
compass.compass_cal_update();
|
||||
}
|
||||
}
|
||||
|
||||
void Sub::accel_cal_update()
|
||||
{
|
||||
if (hal.util->get_soft_armed()) {
|
||||
|
Loading…
Reference in New Issue
Block a user