From d5f57fdd93aa731956060eab3bbefc83c2252f0b Mon Sep 17 00:00:00 2001 From: Lucas De Marchi Date: Wed, 2 Aug 2017 09:08:34 -0700 Subject: [PATCH] AP_Compass: AK8963: remove fallback to timer thread Now that the bus thread from the AuxiliaryBus is implemented we can remove the fallback. --- libraries/AP_Compass/AP_Compass_AK8963.cpp | 27 +--------------------- libraries/AP_Compass/AP_Compass_AK8963.h | 2 -- 2 files changed, 1 insertion(+), 28 deletions(-) diff --git a/libraries/AP_Compass/AP_Compass_AK8963.cpp b/libraries/AP_Compass/AP_Compass_AK8963.cpp index 6922da9d14..49f7e6d81a 100644 --- a/libraries/AP_Compass/AP_Compass_AK8963.cpp +++ b/libraries/AP_Compass/AP_Compass_AK8963.cpp @@ -167,11 +167,7 @@ bool AP_Compass_AK8963::init() bus_sem->give(); - /* timer needs to be called every 10ms so set the freq_div to 10 */ - if (!_bus->register_periodic_callback(10000, FUNCTOR_BIND_MEMBER(&AP_Compass_AK8963::_update, void))) { - // fallback to timer - hal.scheduler->register_timer_process(FUNCTOR_BIND_MEMBER(&AP_Compass_AK8963::_update_timer, void)); - } + _bus->register_periodic_callback(10000, FUNCTOR_BIND_MEMBER(&AP_Compass_AK8963::_update, void)); return true; @@ -264,27 +260,6 @@ void AP_Compass_AK8963::_update() } } -/* - update from timer callback - */ -void AP_Compass_AK8963::_update_timer() -{ - uint32_t now = AP_HAL::micros(); - - if (now - _last_update_timestamp < 10000) { - return; - } - - if (!_bus->get_semaphore()->take_nonblocking()) { - return; - } - - _update(); - _last_update_timestamp = now; - - _bus->get_semaphore()->give(); -} - bool AP_Compass_AK8963::_check_id() { for (int i = 0; i < 5; i++) { diff --git a/libraries/AP_Compass/AP_Compass_AK8963.h b/libraries/AP_Compass/AP_Compass_AK8963.h index 49e798a0a6..eb2d70e681 100644 --- a/libraries/AP_Compass/AP_Compass_AK8963.h +++ b/libraries/AP_Compass/AP_Compass_AK8963.h @@ -51,7 +51,6 @@ private: bool _calibrate(); void _update(); - void _update_timer(); AP_AK8963_BusDriver *_bus; @@ -60,7 +59,6 @@ private: float _mag_y_accum; float _mag_z_accum; uint32_t _accum_count; - uint32_t _last_update_timestamp; uint8_t _compass_instance; bool _initialized;