Sub: moved accel cal update to vehicle code

This commit is contained in:
Andrew Tridgell 2021-08-17 12:52:48 +10:00
parent baec0d83f2
commit dbe0bef58b
3 changed files with 0 additions and 15 deletions

View File

@ -58,7 +58,6 @@ const AP_Scheduler::Task Sub::scheduler_tasks[] = {
SCHED_TASK(rpm_update, 10, 200),
#endif
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
SCHED_TASK_CLASS(AP_Gripper, &sub.g2.gripper, update, 10, 75),

View File

@ -591,7 +591,6 @@ private:
bool verify_nav_delay(const AP_Mission::Mission_Command& cmd);
void log_init(void);
void accel_cal_update(void);
void read_airspeed();
void failsafe_leak_check();

View File

@ -86,19 +86,6 @@ void Sub::rpm_update(void)
}
#endif
void Sub::accel_cal_update()
{
if (hal.util->get_soft_armed()) {
return;
}
ins.acal_update();
// check if new trim values, and set them
float trim_roll, trim_pitch;
if (ins.get_new_trim(trim_roll, trim_pitch)) {
ahrs.set_trim(Vector3f(trim_roll, trim_pitch, 0));
}
}
/*
ask airspeed sensor for a new value, duplicated from plane
*/