HAL_VRBRAIN: removed hal.util->new_semaphore()

replaced with HAL_Semaphore
This commit is contained in:
Andrew Tridgell 2018-10-12 10:35:33 +11:00
parent 44009c5459
commit 725899080e
3 changed files with 36 additions and 43 deletions

View File

@ -68,7 +68,6 @@ VRBRAINAnalogSource::VRBRAINAnalogSource(int16_t pin, float initial_value) :
_sum_value(0),
_sum_ratiometric(0)
{
_semaphore = hal.util->new_semaphore();
}
void VRBRAINAnalogSource::set_stop_pin(uint8_t p)
@ -78,9 +77,9 @@ void VRBRAINAnalogSource::set_stop_pin(uint8_t p)
float VRBRAINAnalogSource::read_average()
{
if (_semaphore->take(1)) {
WITH_SEMAPHORE(_semaphore);
if (_sum_count == 0) {
_semaphore->give();
return _value;
}
_value = _sum_value / _sum_count;
@ -88,9 +87,7 @@ float VRBRAINAnalogSource::read_average()
_sum_value = 0;
_sum_ratiometric = 0;
_sum_count = 0;
_semaphore->give();
return _value;
}
return _value;
}
@ -146,7 +143,9 @@ void VRBRAINAnalogSource::set_pin(uint8_t pin)
if (_pin == pin) {
return;
}
if (_semaphore->take(HAL_SEMAPHORE_BLOCK_FOREVER)) {
WITH_SEMAPHORE(_semaphore);
_pin = pin;
_sum_value = 0;
_sum_ratiometric = 0;
@ -154,8 +153,6 @@ void VRBRAINAnalogSource::set_pin(uint8_t pin)
_latest_value = 0;
_value = 0;
_value_ratiometric = 0;
_semaphore->give();
}
}
/*
@ -163,7 +160,8 @@ void VRBRAINAnalogSource::set_pin(uint8_t pin)
*/
void VRBRAINAnalogSource::_add_value(float v, float vcc5V)
{
if (_semaphore->take(1)) {
WITH_SEMAPHORE(_semaphore);
_latest_value = v;
_sum_value += v;
if (vcc5V < 3.0f) {
@ -179,8 +177,6 @@ void VRBRAINAnalogSource::_add_value(float v, float vcc5V)
_sum_ratiometric /= 2;
_sum_count /= 2;
}
_semaphore->give();
}
}

View File

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

View File

@ -50,9 +50,6 @@ public:
void perf_end(perf_counter_t) override;
void perf_count(perf_counter_t) override;
// create a new semaphore
AP_HAL::Semaphore *new_semaphore(void) override { return new VRBRAIN::Semaphore; }
void set_imu_temp(float current) override;
void set_imu_target_temp(int8_t *target) override;