AP_Baro_Backend.cpp 3.2 KB

123456789101112131415161718192021222324252627282930313233343536373839404142434445464748495051525354555657585960616263646566676869707172737475767778798081828384858687888990919293949596979899
  1. #include "AP_Baro_Backend.h"
  2. #include <stdio.h>
  3. extern const AP_HAL::HAL& hal;
  4. // constructor
  5. AP_Baro_Backend::AP_Baro_Backend(AP_Baro &baro) :
  6. _frontend(baro)
  7. {
  8. }
  9. void AP_Baro_Backend::update_healthy_flag(uint8_t instance)
  10. {
  11. if (instance >= _frontend._num_sensors) {
  12. return;
  13. }
  14. WITH_SEMAPHORE(_sem);
  15. // consider a sensor as healthy if it has had an update in the
  16. // last 0.5 seconds and values are non-zero and have changed within the last 2 seconds
  17. const uint32_t now = AP_HAL::millis();
  18. _frontend.sensors[instance].healthy =
  19. (now - _frontend.sensors[instance].last_update_ms < BARO_TIMEOUT_MS) &&
  20. (now - _frontend.sensors[instance].last_change_ms < BARO_DATA_CHANGE_TIMEOUT_MS) &&
  21. !is_zero(_frontend.sensors[instance].pressure);
  22. if (_frontend.sensors[instance].temperature < -200 ||
  23. _frontend.sensors[instance].temperature > 200) {
  24. // if temperature is way out of range then we likely have bad
  25. // data from the sensor, treat is as unhealthy. This is done
  26. // so SPI sensors which have no data validity checking can
  27. // mark a sensor unhealthy
  28. _frontend.sensors[instance].healthy = false;
  29. }
  30. }
  31. void AP_Baro_Backend::backend_update(uint8_t instance)
  32. {
  33. update();
  34. update_healthy_flag(instance);
  35. }
  36. /*
  37. copy latest data to the frontend from a backend
  38. */
  39. void AP_Baro_Backend::_copy_to_frontend(uint8_t instance, float pressure, float temperature)
  40. {
  41. if (instance >= _frontend._num_sensors) {
  42. return;
  43. }
  44. uint32_t now = AP_HAL::millis();
  45. // check for changes in data values
  46. if (!is_equal(_frontend.sensors[instance].pressure, pressure) || !is_equal(_frontend.sensors[instance].temperature, temperature)) {
  47. _frontend.sensors[instance].last_change_ms = now;
  48. }
  49. // update readings
  50. _frontend.sensors[instance].pressure = pressure;
  51. _frontend.sensors[instance].temperature = temperature;
  52. _frontend.sensors[instance].last_update_ms = now;
  53. }
  54. static constexpr float FILTER_KOEF = 0.1f;
  55. /* Check that the baro value is valid by using a mean filter. If the
  56. * value is further than filtrer_range from mean value, it is
  57. * rejected.
  58. */
  59. bool AP_Baro_Backend::pressure_ok(float press)
  60. {
  61. if (isinf(press) || isnan(press)) {
  62. return false;
  63. }
  64. const float range = (float)_frontend.get_filter_range();
  65. if (range <= 0) {
  66. return true;
  67. }
  68. bool ret = true;
  69. if (is_zero(_mean_pressure)) {
  70. _mean_pressure = press;
  71. } else {
  72. const float d = fabsf(_mean_pressure - press) / (_mean_pressure + press); // diff divide by mean value in percent ( with the * 200.0f on later line)
  73. float koeff = FILTER_KOEF;
  74. if (d * 200.0f > range) { // check the difference from mean value outside allowed range
  75. // printf("\nBaro pressure error: mean %f got %f\n", (double)_mean_pressure, (double)press );
  76. ret = false;
  77. koeff /= (d * 10.0f); // 2.5 and more, so one bad sample never change mean more than 4%
  78. _error_count++;
  79. }
  80. _mean_pressure = _mean_pressure * (1 - koeff) + press * koeff; // complimentary filter 1/k
  81. }
  82. return ret;
  83. }