mirror of https://github.com/ArduPilot/ardupilot
AP_Compass: AK8963: remove fallback to timer thread
Now that the bus thread from the AuxiliaryBus is implemented we can remove the fallback.
This commit is contained in:
parent
06fe5ce8ba
commit
d5f57fdd93
|
@ -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++) {
|
||||
|
|
|
@ -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;
|
||||
|
|
Loading…
Reference in New Issue