mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-02-05 07:28:29 -04:00
Baro: health check that values are changing
This commit is contained in:
parent
2e56e10d9c
commit
6982e58cf2
@ -517,10 +517,10 @@ void AP_Baro::update(void)
|
||||
}
|
||||
|
||||
// consider a sensor as healthy if it has had an update in the
|
||||
// last 0.5 seconds
|
||||
// last 0.5 seconds and values are non-zero and have changed within the last 2 seconds
|
||||
uint32_t now = AP_HAL::millis();
|
||||
for (uint8_t i=0; i<_num_sensors; i++) {
|
||||
sensors[i].healthy = (now - sensors[i].last_update_ms < 500) && !is_zero(sensors[i].pressure);
|
||||
sensors[i].healthy = (now - sensors[i].last_update_ms < BARO_TIMEOUT_MS) && (now - sensors[i].last_change_ms < BARO_DATA_CHANGE_TIMEOUT_MS) && !is_zero(sensors[i].pressure);
|
||||
}
|
||||
|
||||
for (uint8_t i=0; i<_num_sensors; i++) {
|
||||
|
@ -12,6 +12,10 @@
|
||||
// multiple sensor instances
|
||||
#define BARO_MAX_DRIVERS 3
|
||||
|
||||
// timeouts for health reporting
|
||||
#define BARO_TIMEOUT_MS 500 // timeout in ms since last successful read
|
||||
#define BARO_DATA_CHANGE_TIMEOUT_MS 2000 // timeout in ms since last successful read that involved temperature of pressure changing
|
||||
|
||||
class AP_Baro_Backend;
|
||||
|
||||
class AP_Baro
|
||||
@ -169,6 +173,7 @@ private:
|
||||
struct sensor {
|
||||
baro_type_t type; // 0 for air pressure (default), 1 for water pressure
|
||||
uint32_t last_update_ms; // last update time in ms
|
||||
uint32_t last_change_ms; // last update time in ms that included a change in reading from previous readings
|
||||
bool healthy:1; // true if sensor is healthy
|
||||
bool alt_ok:1; // true if calculated altitude is ok
|
||||
bool calibrated:1; // true if calculated calibrated successfully
|
||||
|
@ -17,7 +17,15 @@ void AP_Baro_Backend::_copy_to_frontend(uint8_t instance, float pressure, float
|
||||
if (instance >= _frontend._num_sensors) {
|
||||
return;
|
||||
}
|
||||
uint32_t now = AP_HAL::millis();
|
||||
|
||||
// check for changes in data values
|
||||
if (!is_equal(_frontend.sensors[instance].pressure, pressure) || !is_equal(_frontend.sensors[instance].temperature, temperature)) {
|
||||
_frontend.sensors[instance].last_change_ms = now;
|
||||
}
|
||||
|
||||
// update readings
|
||||
_frontend.sensors[instance].pressure = pressure;
|
||||
_frontend.sensors[instance].temperature = temperature;
|
||||
_frontend.sensors[instance].last_update_ms = AP_HAL::millis();
|
||||
_frontend.sensors[instance].last_update_ms = now;
|
||||
}
|
||||
|
Loading…
Reference in New Issue
Block a user