AP_Baro_Backend.h 1.2 KB

1234567891011121314151617181920212223242526272829303132333435363738394041
  1. #pragma once
  2. #include "AP_Baro.h"
  3. class AP_Baro_Backend
  4. {
  5. public:
  6. AP_Baro_Backend(AP_Baro &baro);
  7. virtual ~AP_Baro_Backend(void) {};
  8. // each driver must provide an update method to copy accumulated
  9. // data to the frontend
  10. virtual void update() = 0;
  11. // accumulate function. This is used for backends that don't use a
  12. // timer, and need to be called regularly by the main code to
  13. // trigger them to read the sensor
  14. virtual void accumulate(void) {}
  15. void backend_update(uint8_t instance);
  16. // Check that the baro valid by using a mean filter.
  17. // If the value further that filtrer_range from mean value, it is rejected.
  18. bool pressure_ok(float press);
  19. uint32_t get_error_count() const { return _error_count; }
  20. protected:
  21. // reference to frontend object
  22. AP_Baro &_frontend;
  23. void _copy_to_frontend(uint8_t instance, float pressure, float temperature);
  24. // semaphore for access to shared frontend data
  25. HAL_Semaphore_Recursive _sem;
  26. virtual void update_healthy_flag(uint8_t instance);
  27. // mean pressure for range filter
  28. float _mean_pressure;
  29. // number of dropped samples. Not used for now, but can be usable to choose more reliable sensor
  30. uint32_t _error_count;
  31. };