mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-02-23 08:13:56 -04:00
AP_Compass: HMC5843: remove useless delay
There's no need to add a delay after suspending timer in the initialization. Also initialize _bus_sem earlier, like is done in AK8963.
This commit is contained in:
parent
c66c9c41f2
commit
9ecd1daf81
@ -244,10 +244,9 @@ AP_Compass_HMC5843::init()
|
|||||||
uint16_t expected_yz = 715;
|
uint16_t expected_yz = 715;
|
||||||
float gain_multiple = 1.0;
|
float gain_multiple = 1.0;
|
||||||
|
|
||||||
hal.scheduler->suspend_timer_procs();
|
|
||||||
hal.scheduler->delay(10);
|
|
||||||
|
|
||||||
_bus_sem = _bus->get_semaphore();
|
_bus_sem = _bus->get_semaphore();
|
||||||
|
hal.scheduler->suspend_timer_procs();
|
||||||
|
|
||||||
if (!_bus_sem->take(HAL_SEMAPHORE_BLOCK_FOREVER)) {
|
if (!_bus_sem->take(HAL_SEMAPHORE_BLOCK_FOREVER)) {
|
||||||
hal.scheduler->panic(PSTR("Failed to get HMC5843 semaphore"));
|
hal.scheduler->panic(PSTR("Failed to get HMC5843 semaphore"));
|
||||||
}
|
}
|
||||||
|
Loading…
Reference in New Issue
Block a user