diff --git a/libraries/AP_Compass/AP_Compass_AK8963.cpp b/libraries/AP_Compass/AP_Compass_AK8963.cpp index c9267e2fab..e8600620d6 100644 --- a/libraries/AP_Compass/AP_Compass_AK8963.cpp +++ b/libraries/AP_Compass/AP_Compass_AK8963.cpp @@ -17,6 +17,7 @@ #include #include +#include #include "AP_Compass_AK8963.h" #include @@ -179,19 +180,19 @@ void AP_Compass_AK8963::read() return; } - if (_sem->take_nonblocking()) { - if (_accum_count == 0) { - /* We're not ready to publish */ - _sem->give(); - return; - } + if (_accum_count == 0) { + return; + } - Vector3f field = Vector3f(_mag_x_accum, _mag_y_accum, _mag_z_accum) / _accum_count; + Vector3f field; + { + WITH_SEMAPHORE(_sem); + field = Vector3f(_mag_x_accum, _mag_y_accum, _mag_z_accum) / _accum_count; _mag_x_accum = _mag_y_accum = _mag_z_accum = 0; _accum_count = 0; - _sem->give(); - publish_filtered_field(field, _compass_instance); } + + publish_filtered_field(field, _compass_instance); } void AP_Compass_AK8963::_make_adc_sensitivity_adjustment(Vector3f& field) const @@ -242,18 +243,17 @@ void AP_Compass_AK8963::_update() // correct raw_field for known errors correct_field(raw_field, _compass_instance); - if (_sem->take(HAL_SEMAPHORE_BLOCK_FOREVER)) { - _mag_x_accum += raw_field.x; - _mag_y_accum += raw_field.y; - _mag_z_accum += raw_field.z; - _accum_count++; - if (_accum_count == 10) { - _mag_x_accum /= 2; - _mag_y_accum /= 2; - _mag_z_accum /= 2; + WITH_SEMAPHORE(_sem); + + _mag_x_accum += raw_field.x; + _mag_y_accum += raw_field.y; + _mag_z_accum += raw_field.z; + _accum_count++; + if (_accum_count == 10) { + _mag_x_accum /= 2; + _mag_y_accum /= 2; + _mag_z_accum /= 2; _accum_count = 5; - } - _sem->give(); } } diff --git a/libraries/AP_Compass/AP_Compass_Backend.cpp b/libraries/AP_Compass/AP_Compass_Backend.cpp index 7d6c8c66f3..37226e330a 100644 --- a/libraries/AP_Compass/AP_Compass_Backend.cpp +++ b/libraries/AP_Compass/AP_Compass_Backend.cpp @@ -11,7 +11,6 @@ extern const AP_HAL::HAL& hal; AP_Compass_Backend::AP_Compass_Backend() : _compass(AP::compass()) { - _sem = hal.util->new_semaphore(); } void AP_Compass_Backend::rotate_field(Vector3f &mag, uint8_t instance) @@ -126,12 +125,9 @@ void AP_Compass_Backend::accumulate_sample(Vector3f &field, uint8_t instance, void AP_Compass_Backend::drain_accumulated_samples(uint8_t instance, const Vector3f *scaling) { - if (!_sem->take_nonblocking()) { - return; - } + WITH_SEMAPHORE(_sem); if (_accum_count == 0) { - _sem->give(); return; } @@ -144,8 +140,6 @@ void AP_Compass_Backend::drain_accumulated_samples(uint8_t instance, _accum.zero(); _accum_count = 0; - - _sem->give(); } /* diff --git a/libraries/AP_Compass/AP_Compass_Backend.h b/libraries/AP_Compass/AP_Compass_Backend.h index 5a20262587..4685c245ee 100644 --- a/libraries/AP_Compass/AP_Compass_Backend.h +++ b/libraries/AP_Compass/AP_Compass_Backend.h @@ -110,7 +110,7 @@ protected: Compass &_compass; // semaphore for access to shared frontend data - AP_HAL::Semaphore *_sem; + HAL_Semaphore_Recursive _sem; // accumulated samples, protected by _sem Vector3f _accum; diff --git a/libraries/AP_Compass/AP_Compass_SITL.cpp b/libraries/AP_Compass/AP_Compass_SITL.cpp index 3bc0592cd9..8d2e6d9929 100644 --- a/libraries/AP_Compass/AP_Compass_SITL.cpp +++ b/libraries/AP_Compass/AP_Compass_SITL.cpp @@ -1,6 +1,7 @@ #include "AP_Compass_SITL.h" #include +#include #if CONFIG_HAL_BOARD == HAL_BOARD_SITL extern const AP_HAL::HAL& hal; @@ -123,9 +124,7 @@ void AP_Compass_SITL::_timer() _mag_accum[i] += f; } - if (!_sem->take(HAL_SEMAPHORE_BLOCK_FOREVER)) { - return; - } + WITH_SEMAPHORE(_sem); _accum_count++; if (_accum_count == 10) { @@ -135,28 +134,24 @@ void AP_Compass_SITL::_timer() _accum_count = 5; _has_sample = true; } - _sem->give(); } void AP_Compass_SITL::read() { - if (_sem->take_nonblocking()) { - if (!_has_sample) { - _sem->give(); - return; - } + WITH_SEMAPHORE(_sem); - for (uint8_t i=0; igive(); + if (!_has_sample) { + return; } + for (uint8_t i=0; inew_semaphore(); - } - return _sem_registry->take(HAL_SEMAPHORE_BLOCK_FOREVER); + return _sem_registry.take(HAL_SEMAPHORE_BLOCK_FOREVER); } void AP_Compass_UAVCAN::give_registry() { - _sem_registry->give(); + _sem_registry.give(); } AP_Compass_Backend* AP_Compass_UAVCAN::probe() diff --git a/libraries/AP_Compass/AP_Compass_UAVCAN.h b/libraries/AP_Compass/AP_Compass_UAVCAN.h index c9688eae60..1a5e4fb5d6 100644 --- a/libraries/AP_Compass/AP_Compass_UAVCAN.h +++ b/libraries/AP_Compass/AP_Compass_UAVCAN.h @@ -48,5 +48,5 @@ private: AP_Compass_UAVCAN *driver; } _detected_modules[COMPASS_MAX_BACKEND]; - static AP_HAL::Semaphore *_sem_registry; + static HAL_Semaphore _sem_registry; }; diff --git a/libraries/AP_Compass/Compass_learn.cpp b/libraries/AP_Compass/Compass_learn.cpp index abf067bb21..5bd31168e3 100644 --- a/libraries/AP_Compass/Compass_learn.cpp +++ b/libraries/AP_Compass/Compass_learn.cpp @@ -48,8 +48,6 @@ void CompassLearn::update(void) R.from_euler(0.0f, -ToRad(inclination_deg), ToRad(declination_deg)); mag_ef = R * mag_ef; - sem = hal.util->new_semaphore(); - have_earth_field = true; // form eliptical correction matrix and invert it. This is @@ -85,8 +83,9 @@ void CompassLearn::update(void) if (field_change.length() < min_field_change) { return; } - - if (sem->take_nonblocking()) { + + { + WITH_SEMAPHORE(sem); // give a sample to the backend to process new_sample.field = field; new_sample.offsets = compass.get_offsets(0); @@ -94,7 +93,6 @@ void CompassLearn::update(void) sample_available = true; last_field = field; num_samples++; - sem->give(); } if (sample_available) { @@ -109,7 +107,9 @@ void CompassLearn::update(void) num_samples); } - if (!converged && sem->take_nonblocking()) { + if (!converged) { + WITH_SEMAPHORE(sem); + // stop updating the offsets once converged compass.set_offsets(0, best_offsets); if (num_samples > 30 && best_error < 50 && worst_error > 65) { @@ -120,7 +120,6 @@ void CompassLearn::update(void) compass.set_learn_type(Compass::LEARN_EKF, true); converged = true; } - sem->give(); } } @@ -132,13 +131,14 @@ void CompassLearn::io_timer(void) if (!sample_available) { return; } + struct sample s; - if (!sem->take_nonblocking()) { - return; + + { + WITH_SEMAPHORE(sem); + s = new_sample; + sample_available = false; } - s = new_sample; - sample_available = false; - sem->give(); process_sample(s); } @@ -192,12 +192,11 @@ void CompassLearn::process_sample(const struct sample &s) } } - if (sem->take_nonblocking()) { - // pass the current estimate to the front-end - best_offsets = predicted_offsets[besti]; - best_error = bestv; - worst_error = worstv; - best_yaw_deg = wrap_360(degrees(s.attitude.z) + besti * (360/num_sectors)); - sem->give(); - } + WITH_SEMAPHORE(sem); + + // pass the current estimate to the front-end + best_offsets = predicted_offsets[besti]; + best_error = bestv; + worst_error = worstv; + best_yaw_deg = wrap_360(degrees(s.attitude.z) + besti * (360/num_sectors)); } diff --git a/libraries/AP_Compass/Compass_learn.h b/libraries/AP_Compass/Compass_learn.h index afb0ebdb70..97f2816a14 100644 --- a/libraries/AP_Compass/Compass_learn.h +++ b/libraries/AP_Compass/Compass_learn.h @@ -30,7 +30,7 @@ private: Vector3f mag_ef; // semaphore for access to shared data with IO thread - AP_HAL::Semaphore *sem; + HAL_Semaphore sem; struct sample { // milliGauss body field and offsets