mirror of https://github.com/ArduPilot/ardupilot
AP_Airspeed: protect sample timestamp while get data
This commit is contained in:
parent
fe889b6f4e
commit
194ea66912
|
@ -98,17 +98,16 @@ void AP_Airspeed_DLVR::timer()
|
||||||
// return the current differential_pressure in Pascal
|
// return the current differential_pressure in Pascal
|
||||||
bool AP_Airspeed_DLVR::get_differential_pressure(float &_pressure)
|
bool AP_Airspeed_DLVR::get_differential_pressure(float &_pressure)
|
||||||
{
|
{
|
||||||
|
WITH_SEMAPHORE(sem);
|
||||||
|
|
||||||
if ((AP_HAL::millis() - last_sample_time_ms) > 100) {
|
if ((AP_HAL::millis() - last_sample_time_ms) > 100) {
|
||||||
return false;
|
return false;
|
||||||
}
|
}
|
||||||
|
|
||||||
{
|
if (press_count > 0) {
|
||||||
WITH_SEMAPHORE(sem);
|
pressure = pressure_sum / press_count;
|
||||||
if (press_count > 0) {
|
press_count = 0;
|
||||||
pressure = pressure_sum / press_count;
|
pressure_sum = 0;
|
||||||
press_count = 0;
|
|
||||||
pressure_sum = 0;
|
|
||||||
}
|
|
||||||
}
|
}
|
||||||
|
|
||||||
_pressure = pressure;
|
_pressure = pressure;
|
||||||
|
@ -118,12 +117,12 @@ bool AP_Airspeed_DLVR::get_differential_pressure(float &_pressure)
|
||||||
// return the current temperature in degrees C, if available
|
// return the current temperature in degrees C, if available
|
||||||
bool AP_Airspeed_DLVR::get_temperature(float &_temperature)
|
bool AP_Airspeed_DLVR::get_temperature(float &_temperature)
|
||||||
{
|
{
|
||||||
|
WITH_SEMAPHORE(sem);
|
||||||
|
|
||||||
if ((AP_HAL::millis() - last_sample_time_ms) > 100) {
|
if ((AP_HAL::millis() - last_sample_time_ms) > 100) {
|
||||||
return false;
|
return false;
|
||||||
}
|
}
|
||||||
|
|
||||||
WITH_SEMAPHORE(sem);
|
|
||||||
|
|
||||||
if (temp_count > 0) {
|
if (temp_count > 0) {
|
||||||
temperature = temperature_sum / temp_count;
|
temperature = temperature_sum / temp_count;
|
||||||
temp_count = 0;
|
temp_count = 0;
|
||||||
|
|
|
@ -223,12 +223,12 @@ void AP_Airspeed_MS4525::_timer()
|
||||||
// return the current differential_pressure in Pascal
|
// return the current differential_pressure in Pascal
|
||||||
bool AP_Airspeed_MS4525::get_differential_pressure(float &pressure)
|
bool AP_Airspeed_MS4525::get_differential_pressure(float &pressure)
|
||||||
{
|
{
|
||||||
|
WITH_SEMAPHORE(sem);
|
||||||
|
|
||||||
if ((AP_HAL::millis() - _last_sample_time_ms) > 100) {
|
if ((AP_HAL::millis() - _last_sample_time_ms) > 100) {
|
||||||
return false;
|
return false;
|
||||||
}
|
}
|
||||||
|
|
||||||
WITH_SEMAPHORE(sem);
|
|
||||||
|
|
||||||
if (_press_count > 0) {
|
if (_press_count > 0) {
|
||||||
_pressure = _press_sum / _press_count;
|
_pressure = _press_sum / _press_count;
|
||||||
_press_count = 0;
|
_press_count = 0;
|
||||||
|
@ -242,12 +242,12 @@ bool AP_Airspeed_MS4525::get_differential_pressure(float &pressure)
|
||||||
// return the current temperature in degrees C, if available
|
// return the current temperature in degrees C, if available
|
||||||
bool AP_Airspeed_MS4525::get_temperature(float &temperature)
|
bool AP_Airspeed_MS4525::get_temperature(float &temperature)
|
||||||
{
|
{
|
||||||
|
WITH_SEMAPHORE(sem);
|
||||||
|
|
||||||
if ((AP_HAL::millis() - _last_sample_time_ms) > 100) {
|
if ((AP_HAL::millis() - _last_sample_time_ms) > 100) {
|
||||||
return false;
|
return false;
|
||||||
}
|
}
|
||||||
|
|
||||||
WITH_SEMAPHORE(sem);
|
|
||||||
|
|
||||||
if (_temp_count > 0) {
|
if (_temp_count > 0) {
|
||||||
_temperature = _temp_sum / _temp_count;
|
_temperature = _temp_sum / _temp_count;
|
||||||
_temp_count = 0;
|
_temp_count = 0;
|
||||||
|
|
|
@ -264,12 +264,12 @@ void AP_Airspeed_MS5525::timer()
|
||||||
// return the current differential_pressure in Pascal
|
// return the current differential_pressure in Pascal
|
||||||
bool AP_Airspeed_MS5525::get_differential_pressure(float &_pressure)
|
bool AP_Airspeed_MS5525::get_differential_pressure(float &_pressure)
|
||||||
{
|
{
|
||||||
|
WITH_SEMAPHORE(sem);
|
||||||
|
|
||||||
if ((AP_HAL::millis() - last_sample_time_ms) > 100) {
|
if ((AP_HAL::millis() - last_sample_time_ms) > 100) {
|
||||||
return false;
|
return false;
|
||||||
}
|
}
|
||||||
|
|
||||||
WITH_SEMAPHORE(sem);
|
|
||||||
|
|
||||||
if (press_count > 0) {
|
if (press_count > 0) {
|
||||||
pressure = pressure_sum / press_count;
|
pressure = pressure_sum / press_count;
|
||||||
press_count = 0;
|
press_count = 0;
|
||||||
|
@ -283,12 +283,12 @@ bool AP_Airspeed_MS5525::get_differential_pressure(float &_pressure)
|
||||||
// return the current temperature in degrees C, if available
|
// return the current temperature in degrees C, if available
|
||||||
bool AP_Airspeed_MS5525::get_temperature(float &_temperature)
|
bool AP_Airspeed_MS5525::get_temperature(float &_temperature)
|
||||||
{
|
{
|
||||||
|
WITH_SEMAPHORE(sem);
|
||||||
|
|
||||||
if ((AP_HAL::millis() - last_sample_time_ms) > 100) {
|
if ((AP_HAL::millis() - last_sample_time_ms) > 100) {
|
||||||
return false;
|
return false;
|
||||||
}
|
}
|
||||||
|
|
||||||
WITH_SEMAPHORE(sem);
|
|
||||||
|
|
||||||
if (temp_count > 0) {
|
if (temp_count > 0) {
|
||||||
temperature = temperature_sum / temp_count;
|
temperature = temperature_sum / temp_count;
|
||||||
temp_count = 0;
|
temp_count = 0;
|
||||||
|
|
|
@ -278,18 +278,16 @@ float AP_Airspeed_SDP3X::_correct_pressure(float press)
|
||||||
// return the current differential_pressure in Pascal
|
// return the current differential_pressure in Pascal
|
||||||
bool AP_Airspeed_SDP3X::get_differential_pressure(float &pressure)
|
bool AP_Airspeed_SDP3X::get_differential_pressure(float &pressure)
|
||||||
{
|
{
|
||||||
uint32_t now = AP_HAL::millis();
|
WITH_SEMAPHORE(sem);
|
||||||
if (now - _last_sample_time_ms > 100) {
|
|
||||||
|
if (AP_HAL::millis() - _last_sample_time_ms > 100) {
|
||||||
return false;
|
return false;
|
||||||
}
|
}
|
||||||
|
|
||||||
{
|
if (_press_count > 0) {
|
||||||
WITH_SEMAPHORE(sem);
|
_press = _press_sum / _press_count;
|
||||||
if (_press_count > 0) {
|
_press_count = 0;
|
||||||
_press = _press_sum / _press_count;
|
_press_sum = 0;
|
||||||
_press_count = 0;
|
|
||||||
_press_sum = 0;
|
|
||||||
}
|
|
||||||
}
|
}
|
||||||
|
|
||||||
pressure = _correct_pressure(_press);
|
pressure = _correct_pressure(_press);
|
||||||
|
@ -299,12 +297,12 @@ bool AP_Airspeed_SDP3X::get_differential_pressure(float &pressure)
|
||||||
// return the current temperature in degrees C, if available
|
// return the current temperature in degrees C, if available
|
||||||
bool AP_Airspeed_SDP3X::get_temperature(float &temperature)
|
bool AP_Airspeed_SDP3X::get_temperature(float &temperature)
|
||||||
{
|
{
|
||||||
|
WITH_SEMAPHORE(sem);
|
||||||
|
|
||||||
if ((AP_HAL::millis() - _last_sample_time_ms) > 100) {
|
if ((AP_HAL::millis() - _last_sample_time_ms) > 100) {
|
||||||
return false;
|
return false;
|
||||||
}
|
}
|
||||||
|
|
||||||
WITH_SEMAPHORE(sem);
|
|
||||||
|
|
||||||
if (_temp_count > 0) {
|
if (_temp_count > 0) {
|
||||||
_temp = _temp_sum / _temp_count;
|
_temp = _temp_sum / _temp_count;
|
||||||
_temp_count = 0;
|
_temp_count = 0;
|
||||||
|
|
Loading…
Reference in New Issue