AP_Compass: HMC5843: release the lock before read

read() calls accumulate() which takes the lock by itself so we must
release it like we were doing before 669ae26 ("AP_Compass: encapsulated
calibration in HMC").
This commit is contained in:
Lucas De Marchi 2015-08-10 16:50:29 -03:00 committed by Andrew Tridgell
parent a9e8c1c464
commit f61386ae43

View File

@ -260,6 +260,11 @@ AP_Compass_HMC5843::init()
goto errout;
}
_initialised = true;
_i2c_sem->give();
hal.scheduler->resume_timer_procs();
// perform an initial read
read();
#if 0
@ -270,14 +275,9 @@ AP_Compass_HMC5843::init()
_compass_instance = register_compass();
set_dev_id(_compass_instance, _product_id);
_initialised = true;
_i2c_sem->give();
hal.scheduler->resume_timer_procs();
return true;
errout:
errout:
_i2c_sem->give();
hal.scheduler->resume_timer_procs();
return false;