Browse Source

HAL_PX4: removed hal.util->new_semaphore()

replaced with HAL_Semaphore
master
Andrew Tridgell 6 years ago
parent
commit
a9fbe106c9
  1. 20
      libraries/AP_HAL_PX4/AnalogIn.cpp
  2. 2
      libraries/AP_HAL_PX4/AnalogIn.h
  3. 3
      libraries/AP_HAL_PX4/Util.h

20
libraries/AP_HAL_PX4/AnalogIn.cpp

@ -17,6 +17,7 @@ @@ -17,6 +17,7 @@
#include <GCS_MAVLink/GCS_MAVLink.h>
#include <errno.h>
#include "GPIO.h"
#include <AP_Common/Semaphore.h>
#define ANLOGIN_DEBUGGING 0
@ -79,7 +80,6 @@ PX4AnalogSource::PX4AnalogSource(int16_t pin, float initial_value) : @@ -79,7 +80,6 @@ PX4AnalogSource::PX4AnalogSource(int16_t pin, float initial_value) :
_sum_value(0),
_sum_ratiometric(0)
{
_semaphore = hal.util->new_semaphore();
#ifdef PX4_ANALOG_VCC_5V_PIN
if (_pin == ANALOG_INPUT_BOARD_VCC) {
_pin = PX4_ANALOG_VCC_5V_PIN;
@ -94,9 +94,9 @@ void PX4AnalogSource::set_stop_pin(uint8_t p) @@ -94,9 +94,9 @@ void PX4AnalogSource::set_stop_pin(uint8_t p)
float PX4AnalogSource::read_average()
{
if (_semaphore->take(1)) {
WITH_SEMAPHORE(_semaphore);
if (_sum_count == 0) {
_semaphore->give();
return _value;
}
_value = _sum_value / _sum_count;
@ -104,9 +104,7 @@ float PX4AnalogSource::read_average() @@ -104,9 +104,7 @@ float PX4AnalogSource::read_average()
_sum_value = 0;
_sum_ratiometric = 0;
_sum_count = 0;
_semaphore->give();
return _value;
}
return _value;
}
@ -162,7 +160,8 @@ void PX4AnalogSource::set_pin(uint8_t pin) @@ -162,7 +160,8 @@ void PX4AnalogSource::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;
@ -170,8 +169,6 @@ void PX4AnalogSource::set_pin(uint8_t pin) @@ -170,8 +169,6 @@ void PX4AnalogSource::set_pin(uint8_t pin)
_latest_value = 0;
_value = 0;
_value_ratiometric = 0;
_semaphore->give();
}
}
/*
@ -179,7 +176,8 @@ void PX4AnalogSource::set_pin(uint8_t pin) @@ -179,7 +176,8 @@ void PX4AnalogSource::set_pin(uint8_t pin)
*/
void PX4AnalogSource::_add_value(float v, float vcc5V)
{
if (_semaphore->take(1)) {
WITH_SEMAPHORE(_semaphore);
_latest_value = v;
_sum_value += v;
if (vcc5V < 3.0f) {
@ -195,8 +193,6 @@ void PX4AnalogSource::_add_value(float v, float vcc5V) @@ -195,8 +193,6 @@ void PX4AnalogSource::_add_value(float v, float vcc5V)
_sum_ratiometric /= 2;
_sum_count /= 2;
}
_semaphore->give();
}
}

2
libraries/AP_HAL_PX4/AnalogIn.h

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

3
libraries/AP_HAL_PX4/Util.h

@ -50,9 +50,6 @@ public: @@ -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 PX4::Semaphore; }
void set_imu_temp(float current) override;
void set_imu_target_temp(int8_t *target) override;

Loading…
Cancel
Save