From 65c878c06f4b87646b59d51464336121a62007b2 Mon Sep 17 00:00:00 2001 From: Andrew Tridgell Date: Tue, 17 Aug 2021 12:52:48 +1000 Subject: [PATCH] Blimp: moved accel cal update to vehicle code --- Blimp/Blimp.cpp | 1 - Blimp/Blimp.h | 1 - Blimp/sensors.cpp | 20 -------------------- 3 files changed, 22 deletions(-) diff --git a/Blimp/Blimp.cpp b/Blimp/Blimp.cpp index f8b89787ba..2ce7b0cf7c 100644 --- a/Blimp/Blimp.cpp +++ b/Blimp/Blimp.cpp @@ -57,7 +57,6 @@ const AP_Scheduler::Task Blimp::scheduler_tasks[] = { SCHED_TASK_CLASS(AP_InertialSensor, &blimp.ins, periodic, 400, 50), SCHED_TASK_CLASS(AP_Scheduler, &blimp.scheduler, update_logging, 0.1, 75), SCHED_TASK_CLASS(Compass, &blimp.compass, cal_update, 100, 100), - SCHED_TASK(accel_cal_update, 10, 100), #if STATS_ENABLED == ENABLED SCHED_TASK_CLASS(AP_Stats, &blimp.g2.stats, update, 1, 100), #endif diff --git a/Blimp/Blimp.h b/Blimp/Blimp.h index 5ac5059295..30d15acbb0 100644 --- a/Blimp/Blimp.h +++ b/Blimp/Blimp.h @@ -427,7 +427,6 @@ private: bool rangefinder_up_ok(); void rpm_update(); void update_optical_flow(void); - void accel_cal_update(void); void init_proximity(); void update_proximity(); diff --git a/Blimp/sensors.cpp b/Blimp/sensors.cpp index b52366d039..441c482f5a 100644 --- a/Blimp/sensors.cpp +++ b/Blimp/sensors.cpp @@ -7,23 +7,3 @@ void Blimp::read_barometer(void) baro_alt = barometer.get_altitude() * 100.0f; } - -void Blimp::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 -}