mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-22 00:28:30 -04:00
HAL_PX4: removed hal.util->new_semaphore()
replaced with HAL_Semaphore
This commit is contained in:
parent
63556b9804
commit
a9fbe106c9
@ -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) :
|
||||
_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,19 +94,17 @@ void PX4AnalogSource::set_stop_pin(uint8_t p)
|
||||
|
||||
float PX4AnalogSource::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;
|
||||
}
|
||||
|
||||
@ -162,16 +160,15 @@ void PX4AnalogSource::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;
|
||||
}
|
||||
|
||||
/*
|
||||
@ -179,23 +176,22 @@ void PX4AnalogSource::set_pin(uint8_t pin)
|
||||
*/
|
||||
void PX4AnalogSource::_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;
|
||||
}
|
||||
}
|
||||
|
||||
|
@ -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 {
|
||||
|
@ -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…
Reference in New Issue
Block a user