HAL_ChibiOS: removed hal.util->new_semaphore()

replaced with HAL_Semaphore
This commit is contained in:
Andrew Tridgell 2018-10-12 10:35:32 +11:00
parent b455c7a769
commit 4416404137
3 changed files with 36 additions and 41 deletions

View File

@ -17,6 +17,7 @@
#include <AP_HAL/AP_HAL.h>
#include "ch.h"
#include "hal.h"
#include <AP_Common/Semaphore.h>
#if HAL_USE_ADC == TRUE
@ -76,24 +77,22 @@ AnalogSource::AnalogSource(int16_t pin, float initial_value) :
_sum_value(0),
_sum_ratiometric(0)
{
_semaphore = hal.util->new_semaphore();
}
float AnalogSource::read_average()
{
if (_semaphore->take(1)) {
if (_sum_count == 0) {
_semaphore->give();
return _value;
}
_value = _sum_value / _sum_count;
_value_ratiometric = _sum_ratiometric / _sum_count;
_sum_value = 0;
_sum_ratiometric = 0;
_sum_count = 0;
_semaphore->give();
WITH_SEMAPHORE(_semaphore);
if (_sum_count == 0) {
return _value;
}
_value = _sum_value / _sum_count;
_value_ratiometric = _sum_ratiometric / _sum_count;
_sum_value = 0;
_sum_ratiometric = 0;
_sum_count = 0;
return _value;
}
@ -148,16 +147,14 @@ void AnalogSource::set_pin(uint8_t pin)
if (_pin == pin) {
return;
}
if (_semaphore->take(HAL_SEMAPHORE_BLOCK_FOREVER)) {
_pin = pin;
_sum_value = 0;
_sum_ratiometric = 0;
_sum_count = 0;
_latest_value = 0;
_value = 0;
_value_ratiometric = 0;
_semaphore->give();
}
WITH_SEMAPHORE(_semaphore);
_pin = pin;
_sum_value = 0;
_sum_ratiometric = 0;
_sum_count = 0;
_latest_value = 0;
_value = 0;
_value_ratiometric = 0;
}
/*
@ -165,23 +162,22 @@ void AnalogSource::set_pin(uint8_t pin)
*/
void AnalogSource::_add_value(float v, float vcc5V)
{
if (_semaphore->take(1)) {
_latest_value = v;
_sum_value += v;
if (vcc5V < 3.0f) {
_sum_ratiometric += v;
} else {
// this compensates for changes in the 5V rail relative to the
// 3.3V reference used by the ADC.
_sum_ratiometric += v * 5.0f / vcc5V;
}
_sum_count++;
if (_sum_count == 254) {
_sum_value /= 2;
_sum_ratiometric /= 2;
_sum_count /= 2;
}
_semaphore->give();
WITH_SEMAPHORE(_semaphore);
_latest_value = v;
_sum_value += v;
if (vcc5V < 3.0f) {
_sum_ratiometric += v;
} else {
// this compensates for changes in the 5V rail relative to the
// 3.3V reference used by the ADC.
_sum_ratiometric += v * 5.0f / vcc5V;
}
_sum_count++;
if (_sum_count == 254) {
_sum_value /= 2;
_sum_ratiometric /= 2;
_sum_count /= 2;
}
}

View File

@ -50,7 +50,7 @@ private:
float _sum_ratiometric;
void _add_value(float v, float vcc5V);
float _pin_scaler();
AP_HAL::Semaphore *_semaphore;
HAL_Semaphore _semaphore;
};
class ChibiOS::AnalogIn : public AP_HAL::AnalogIn {

View File

@ -27,7 +27,6 @@ public:
}
bool run_debug_shell(AP_HAL::BetterStream *stream) override { return false; }
AP_HAL::Semaphore *new_semaphore(void) override { return new ChibiOS::Semaphore; }
uint32_t available_memory() override;
// Special Allocation Routines