From f61386ae432cde2b454f01ec45486baa48c3e5f0 Mon Sep 17 00:00:00 2001 From: Lucas De Marchi Date: Mon, 10 Aug 2015 16:50:29 -0300 Subject: [PATCH] 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"). --- libraries/AP_Compass/AP_Compass_HMC5843.cpp | 12 ++++++------ 1 file changed, 6 insertions(+), 6 deletions(-) diff --git a/libraries/AP_Compass/AP_Compass_HMC5843.cpp b/libraries/AP_Compass/AP_Compass_HMC5843.cpp index fcaa695b58..e17b373e99 100644 --- a/libraries/AP_Compass/AP_Compass_HMC5843.cpp +++ b/libraries/AP_Compass/AP_Compass_HMC5843.cpp @@ -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;