From ab36dc0ed916f041a187ea4ac70faa2f878f0c49 Mon Sep 17 00:00:00 2001 From: Andrew Tridgell Date: Tue, 17 Aug 2021 12:52:48 +1000 Subject: [PATCH] Copter: moved accel cal update to vehicle code --- ArduCopter/Copter.cpp | 1 - ArduCopter/Copter.h | 2 +- ArduCopter/sensors.cpp | 20 -------------------- 3 files changed, 1 insertion(+), 22 deletions(-) diff --git a/ArduCopter/Copter.cpp b/ArduCopter/Copter.cpp index 35a6688a55..ce192c7a4b 100644 --- a/ArduCopter/Copter.cpp +++ b/ArduCopter/Copter.cpp @@ -167,7 +167,6 @@ const AP_Scheduler::Task Copter::scheduler_tasks[] = { SCHED_TASK(rpm_update, 40, 200), #endif 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), #if HAL_ADSB_ENABLED SCHED_TASK(avoidance_adsb_update, 10, 100), diff --git a/ArduCopter/Copter.h b/ArduCopter/Copter.h index 1c0fec88df..79f80168cd 100644 --- a/ArduCopter/Copter.h +++ b/ArduCopter/Copter.h @@ -869,7 +869,7 @@ private: bool rangefinder_up_ok() const; void rpm_update(); void update_optical_flow(void); - void accel_cal_update(void); + void compass_cal_update(void); void init_proximity(); void update_proximity(); diff --git a/ArduCopter/sensors.cpp b/ArduCopter/sensors.cpp index 243d0cb981..6955e211d5 100644 --- a/ArduCopter/sensors.cpp +++ b/ArduCopter/sensors.cpp @@ -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 void Copter::init_proximity(void) {