Path: blob/master/libraries/AP_Baro/AP_Baro_Backend.cpp
9451 views
#include "AP_Baro_Backend.h"12#include <stdio.h>3#include <AP_Math/AP_Math.h>4#include <AP_Vehicle/AP_Vehicle_Type.h>56extern const AP_HAL::HAL& hal;78#ifndef AP_BARO_DATA_CHANGE_TIMEOUT_MS9#if APM_BUILD_TYPE(APM_BUILD_ArduSub)10#define AP_BARO_DATA_CHANGE_TIMEOUT_MS 20000 // timeout in ms since last successful read that involved temperature of pressure changing11#else12#define AP_BARO_DATA_CHANGE_TIMEOUT_MS 2000 // timeout in ms since last successful read that involved temperature of pressure changing13#endif // APM_BUILD_ArduSub14#endif // ifndef(AP_BARO_DATA_CHANGE_TIMEOUT_MS)1516// constructor17AP_Baro_Backend::AP_Baro_Backend(AP_Baro &baro) :18_frontend(baro)19{20}2122void AP_Baro_Backend::set_bus_id(uint8_t instance, uint32_t id)23{24_frontend.sensors[instance].bus_id.set(int32_t(id));25}2627void AP_Baro_Backend::update_healthy_flag(uint8_t instance)28{29if (instance >= _frontend._num_sensors) {30return;31}32WITH_SEMAPHORE(_sem);3334// consider a sensor as healthy if it has had an update in the35// last 0.5 seconds and values are non-zero and have changed within the last 2 seconds36const uint32_t now = AP_HAL::millis();37_frontend.sensors[instance].healthy =38(now - _frontend.sensors[instance].last_update_ms < BARO_TIMEOUT_MS) &&39(now - _frontend.sensors[instance].last_change_ms < AP_BARO_DATA_CHANGE_TIMEOUT_MS) &&40!is_zero(_frontend.sensors[instance].pressure);4142if (_frontend.sensors[instance].temperature < -200 ||43_frontend.sensors[instance].temperature > 200) {44// if temperature is way out of range then we likely have bad45// data from the sensor, treat is as unhealthy. This is done46// so SPI sensors which have no data validity checking can47// mark a sensor unhealthy48_frontend.sensors[instance].healthy = false;49}50}5152void AP_Baro_Backend::backend_update(uint8_t instance)53{54update();55update_healthy_flag(instance);56}575859/*60copy latest data to the frontend from a backend61*/62void AP_Baro_Backend::_copy_to_frontend(uint8_t instance, float pressure, float temperature)63{64if (instance >= _frontend._num_sensors) {65return;66}67uint32_t now = AP_HAL::millis();6869// check for changes in data values70if (!is_equal(_frontend.sensors[instance].pressure, pressure) || !is_equal(_frontend.sensors[instance].temperature, temperature)) {71_frontend.sensors[instance].last_change_ms = now;72}7374// update readings75_frontend.sensors[instance].pressure = pressure;76_frontend.sensors[instance].temperature = temperature;77_frontend.sensors[instance].last_update_ms = now;78}7980static constexpr float FILTER_KOEF = 0.1f;8182/* Check that the baro value is valid by using a mean filter. If the83* value is further than filter_range from mean value, it is84* rejected.85*/86bool AP_Baro_Backend::pressure_ok(float press)87{8889if (isinf(press) || isnan(press)) {90return false;91}9293const float range = (float)_frontend.get_filter_range();94if (range <= 0) {95return true;96}9798bool ret = true;99if (is_zero(_mean_pressure)) {100_mean_pressure = press;101} else {102const float d = fabsf(_mean_pressure - press) / (_mean_pressure + press); // diff divide by mean value in percent ( with the * 200.0f on later line)103float koeff = FILTER_KOEF;104105if (d * 200.0f > range) { // check the difference from mean value outside allowed range106// printf("\nBaro pressure error: mean %f got %f\n", (double)_mean_pressure, (double)press );107ret = false;108koeff /= (d * 10.0f); // 2.5 and more, so one bad sample never change mean more than 4%109_error_count++;110}111_mean_pressure = _mean_pressure * (1 - koeff) + press * koeff; // complimentary filter 1/k112}113return ret;114}115116117