Copter: moved accel cal update to vehicle code

This commit is contained in:
Andrew Tridgell 2021-08-17 12:52:48 +10:00
parent 39b4825442
commit ab36dc0ed9
3 changed files with 1 additions and 22 deletions

View File

@ -167,7 +167,6 @@ const AP_Scheduler::Task Copter::scheduler_tasks[] = {
SCHED_TASK(rpm_update, 40, 200), SCHED_TASK(rpm_update, 40, 200),
#endif #endif
SCHED_TASK_CLASS(Compass, &copter.compass, cal_update, 100, 100), SCHED_TASK_CLASS(Compass, &copter.compass, cal_update, 100, 100),
SCHED_TASK(accel_cal_update, 10, 100),
SCHED_TASK_CLASS(AP_TempCalibration, &copter.g2.temp_calibration, update, 10, 100), SCHED_TASK_CLASS(AP_TempCalibration, &copter.g2.temp_calibration, update, 10, 100),
#if HAL_ADSB_ENABLED #if HAL_ADSB_ENABLED
SCHED_TASK(avoidance_adsb_update, 10, 100), SCHED_TASK(avoidance_adsb_update, 10, 100),

View File

@ -869,7 +869,7 @@ private:
bool rangefinder_up_ok() const; bool rangefinder_up_ok() const;
void rpm_update(); void rpm_update();
void update_optical_flow(void); void update_optical_flow(void);
void accel_cal_update(void); void compass_cal_update(void);
void init_proximity(); void init_proximity();
void update_proximity(); void update_proximity();

View File

@ -163,26 +163,6 @@ void Copter::rpm_update(void)
} }
void Copter::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));
}
#ifdef CAL_ALWAYS_REBOOT
if (ins.accel_cal_requires_reboot()) {
hal.scheduler->delay(1000);
hal.scheduler->reboot(false);
}
#endif
}
// initialise proximity sensor // initialise proximity sensor
void Copter::init_proximity(void) void Copter::init_proximity(void)
{ {