mirror of https://github.com/ArduPilot/ardupilot
AP_Airspeed: use raw (signed) airspeed
this allows us to detect when the user has the ports the wrong way around, and mark the sensor unhealthy
This commit is contained in:
parent
0a3476bbf1
commit
dcd7f9d26d
|
@ -180,8 +180,19 @@ void AP_Airspeed::read(void)
|
|||
if (!_enable) {
|
||||
return;
|
||||
}
|
||||
airspeed_pressure = get_pressure();
|
||||
airspeed_pressure = max(airspeed_pressure - _offset, 0);
|
||||
/*
|
||||
when we get negative pressures it means the tubes are probably
|
||||
connected the wrong way around. We don't just use the absolute
|
||||
value as otherwise we could get bad readings in some flight
|
||||
attitudes (eg. a spin) due to pressure on the static port
|
||||
*/
|
||||
airspeed_pressure = get_pressure() - _offset;
|
||||
if (airspeed_pressure < -32) {
|
||||
// we're reading more than about -8m/s. The user probably has
|
||||
// the ports the wrong way around
|
||||
_healthy = false;
|
||||
}
|
||||
airspeed_pressure = max(airspeed_pressure, 0);
|
||||
_last_pressure = airspeed_pressure;
|
||||
_raw_airspeed = sqrtf(airspeed_pressure * _ratio);
|
||||
_airspeed = 0.7f * _airspeed + 0.3f * _raw_airspeed;
|
||||
|
|
|
@ -88,7 +88,7 @@ public:
|
|||
|
||||
// return true if airspeed is enabled, and airspeed use is set
|
||||
bool use(void) const {
|
||||
return _enable && _use && _offset > 0 && _healthy;
|
||||
return _enable && _use && fabsf(_offset) > 0 && _healthy;
|
||||
}
|
||||
|
||||
// return true if airspeed is enabled
|
||||
|
|
|
@ -82,8 +82,22 @@ void AP_Airspeed_I2C::_collect(void)
|
|||
dT_raw = (data[2] << 8) + data[3];
|
||||
dT_raw = (0xFFE0 & dT_raw) >> 5;
|
||||
|
||||
_temperature = ((200 * dT_raw) / 2047) - 50;
|
||||
_pressure = fabs(dp_raw - (16384 / 2.0f));
|
||||
const float P_min = -1.0f;
|
||||
const float P_max = 1.0f;
|
||||
const float PSI_to_Pa = 6894.757f;
|
||||
/*
|
||||
this equation is an inversion of the equation in the
|
||||
pressure transfer function figure on page 4 of the datasheet
|
||||
|
||||
We negate the result so that positive differential pressures
|
||||
are generated when the bottom port is used as the static
|
||||
port on the pitot and top port is used as the dynamic port
|
||||
*/
|
||||
float diff_press_PSI = -((dp_raw - 0.1f*16383) * (P_max-P_min)/(0.8f*16383) + P_min);
|
||||
|
||||
_pressure = diff_press_PSI * PSI_to_Pa;
|
||||
_temperature = ((200.0f * dT_raw) / 2047) - 50;
|
||||
|
||||
_last_sample_time_ms = hal.scheduler->millis();
|
||||
}
|
||||
|
||||
|
|
|
@ -60,7 +60,7 @@ bool AP_Airspeed_PX4::get_differential_pressure(float &pressure)
|
|||
|
||||
while (::read(_fd, &report, sizeof(report)) == sizeof(report) &&
|
||||
report.timestamp != _last_timestamp) {
|
||||
psum += report.differential_pressure_pa;
|
||||
psum += report.differential_pressure_raw_pa;
|
||||
tsum += report.temperature;
|
||||
count++;
|
||||
_last_timestamp = report.timestamp;
|
||||
|
|
Loading…
Reference in New Issue