APM:Libraries
AP_Baro_Backend.h
Go to the documentation of this file.
1 #pragma once
2 
3 #include "AP_Baro.h"
4 
6 {
7 public:
9  virtual ~AP_Baro_Backend(void) {};
10 
11  // each driver must provide an update method to copy accumulated
12  // data to the frontend
13  virtual void update() = 0;
14 
15  // accumulate function. This is used for backends that don't use a
16  // timer, and need to be called regularly by the main code to
17  // trigger them to read the sensor
18  virtual void accumulate(void) {}
19 
20  // callback for UAVCAN messages
21  virtual void handle_baro_msg(float pressure, float temperature) {}
22 
23  void backend_update(uint8_t instance);
24 
25  // Check that the baro valid by using a mean filter.
26  // If the value further that filtrer_range from mean value, it is rejected.
27  bool pressure_ok(float press);
28  uint32_t get_error_count() const { return _error_count; }
29 protected:
30  // reference to frontend object
32 
33  void _copy_to_frontend(uint8_t instance, float pressure, float temperature);
34 
35  // semaphore for access to shared frontend data
37 
38  virtual void update_healthy_flag(uint8_t instance);
39 
40  // mean pressure for range filter
42  // number of dropped samples. Not used for now, but can be usable to choose more reliable sensor
43  uint32_t _error_count;
44 };
uint32_t get_error_count() const
uint32_t _error_count
virtual void update_healthy_flag(uint8_t instance)
void _copy_to_frontend(uint8_t instance, float pressure, float temperature)
AP_HAL::Semaphore * _sem
virtual void accumulate(void)
float temperature
Definition: Airspeed.cpp:32
AP_Baro & _frontend
static AP_Baro baro
Definition: ModuleTest.cpp:18
virtual ~AP_Baro_Backend(void)
bool pressure_ok(float press)
void backend_update(uint8_t instance)
AP_Baro_Backend(AP_Baro &baro)
virtual void handle_baro_msg(float pressure, float temperature)
virtual void update()=0