2015-12-01 12:07:15 -04:00
|
|
|
#pragma once
|
2014-10-19 16:22:51 -03:00
|
|
|
|
|
|
|
#include "AP_Baro.h"
|
|
|
|
|
2022-01-26 23:58:56 -04:00
|
|
|
#ifndef AP_BARO_BACKEND_DEFAULT_ENABLED
|
|
|
|
#define AP_BARO_BACKEND_DEFAULT_ENABLED 1
|
|
|
|
#endif
|
|
|
|
|
2014-10-19 16:22:51 -03:00
|
|
|
class AP_Baro_Backend
|
|
|
|
{
|
|
|
|
public:
|
|
|
|
AP_Baro_Backend(AP_Baro &baro);
|
2017-04-02 11:56:03 -03:00
|
|
|
virtual ~AP_Baro_Backend(void) {};
|
2014-10-19 16:22:51 -03:00
|
|
|
|
|
|
|
// each driver must provide an update method to copy accumulated
|
|
|
|
// data to the frontend
|
|
|
|
virtual void update() = 0;
|
|
|
|
|
|
|
|
// accumulate function. This is used for backends that don't use a
|
|
|
|
// timer, and need to be called regularly by the main code to
|
|
|
|
// trigger them to read the sensor
|
|
|
|
virtual void accumulate(void) {}
|
|
|
|
|
2017-07-12 02:03:33 -03:00
|
|
|
void backend_update(uint8_t instance);
|
|
|
|
|
2018-03-12 04:58:10 -03:00
|
|
|
// Check that the baro valid by using a mean filter.
|
|
|
|
// If the value further that filtrer_range from mean value, it is rejected.
|
|
|
|
bool pressure_ok(float press);
|
|
|
|
uint32_t get_error_count() const { return _error_count; }
|
2020-07-18 04:12:41 -03:00
|
|
|
|
2022-01-26 23:58:56 -04:00
|
|
|
#if AP_BARO_MSP_ENABLED
|
2020-09-03 19:09:52 -03:00
|
|
|
virtual void handle_msp(const MSP::msp_baro_data_message_t &pkt) {}
|
2022-01-26 23:58:56 -04:00
|
|
|
#endif
|
2020-09-03 19:09:52 -03:00
|
|
|
|
2022-01-26 23:58:56 -04:00
|
|
|
#if AP_BARO_EXTERNALAHRS_ENABLED
|
2020-12-27 22:05:33 -04:00
|
|
|
virtual void handle_external(const AP_ExternalAHRS::baro_data_message_t &pkt) {}
|
2022-01-26 23:58:56 -04:00
|
|
|
#endif
|
|
|
|
|
2020-07-18 04:12:41 -03:00
|
|
|
/*
|
|
|
|
device driver IDs. These are used to fill in the devtype field
|
2020-12-03 04:12:39 -04:00
|
|
|
of the device ID, which shows up as BARO_DEVID* parameters to
|
2020-07-18 04:12:41 -03:00
|
|
|
users.
|
|
|
|
*/
|
|
|
|
enum DevTypes {
|
|
|
|
DEVTYPE_BARO_SITL = 0x01,
|
|
|
|
DEVTYPE_BARO_BMP085 = 0x02,
|
|
|
|
DEVTYPE_BARO_BMP280 = 0x03,
|
|
|
|
DEVTYPE_BARO_BMP388 = 0x04,
|
|
|
|
DEVTYPE_BARO_DPS280 = 0x05,
|
|
|
|
DEVTYPE_BARO_DPS310 = 0x06,
|
|
|
|
DEVTYPE_BARO_FBM320 = 0x07,
|
|
|
|
DEVTYPE_BARO_ICM20789 = 0x08,
|
|
|
|
DEVTYPE_BARO_KELLERLD = 0x09,
|
|
|
|
DEVTYPE_BARO_LPS2XH = 0x0A,
|
|
|
|
DEVTYPE_BARO_MS5611 = 0x0B,
|
|
|
|
DEVTYPE_BARO_SPL06 = 0x0C,
|
|
|
|
DEVTYPE_BARO_UAVCAN = 0x0D,
|
2020-09-03 19:09:52 -03:00
|
|
|
DEVTYPE_BARO_MSP = 0x0E,
|
2022-06-01 22:53:24 -03:00
|
|
|
DEVTYPE_BARO_ICP101XX = 0x0F,
|
2022-06-24 03:17:22 -03:00
|
|
|
DEVTYPE_BARO_ICP201XX = 0x10,
|
2022-10-16 07:52:18 -03:00
|
|
|
DEVTYPE_BARO_MS5607 = 0x11,
|
|
|
|
DEVTYPE_BARO_MS5837 = 0x12,
|
|
|
|
DEVTYPE_BARO_MS5637 = 0x13,
|
2022-10-03 19:02:00 -03:00
|
|
|
DEVTYPE_BARO_BMP390 = 0x14,
|
2020-07-18 04:12:41 -03:00
|
|
|
};
|
|
|
|
|
2014-10-19 16:22:51 -03:00
|
|
|
protected:
|
|
|
|
// reference to frontend object
|
|
|
|
AP_Baro &_frontend;
|
|
|
|
|
|
|
|
void _copy_to_frontend(uint8_t instance, float pressure, float temperature);
|
2016-11-03 22:05:12 -03:00
|
|
|
|
|
|
|
// semaphore for access to shared frontend data
|
2020-01-18 17:57:22 -04:00
|
|
|
HAL_Semaphore _sem;
|
2017-07-12 02:03:33 -03:00
|
|
|
|
|
|
|
virtual void update_healthy_flag(uint8_t instance);
|
|
|
|
|
2018-03-12 04:58:10 -03:00
|
|
|
// mean pressure for range filter
|
|
|
|
float _mean_pressure;
|
|
|
|
// number of dropped samples. Not used for now, but can be usable to choose more reliable sensor
|
|
|
|
uint32_t _error_count;
|
2020-07-18 04:12:41 -03:00
|
|
|
|
2020-12-03 04:12:39 -04:00
|
|
|
// set bus ID of this instance, for BARO_DEVID parameters
|
2020-07-18 04:12:41 -03:00
|
|
|
void set_bus_id(uint8_t instance, uint32_t id) {
|
|
|
|
_frontend.sensors[instance].bus_id.set(int32_t(id));
|
|
|
|
}
|
2014-10-19 16:22:51 -03:00
|
|
|
};
|