Path: blob/master/libraries/AP_Baro/AP_Baro_DPS280.h
9743 views
#pragma once12#include "AP_Baro_Backend.h"34#if AP_BARO_DPS280_ENABLED56#include <AP_HAL/AP_HAL.h>7#include <AP_HAL/Device.h>89#ifndef HAL_BARO_DPS280_I2C_ADDR10#define HAL_BARO_DPS280_I2C_ADDR 0x7611#endif12#ifndef HAL_BARO_DPS280_I2C_ADDR213#define HAL_BARO_DPS280_I2C_ADDR2 0x7714#endif1516class AP_Baro_DPS280 : public AP_Baro_Backend {17public:18AP_Baro_DPS280(AP_Baro &baro, AP_HAL::Device &dev);1920/* AP_Baro public interface: */21void update() override;2223static AP_Baro_Backend *probe_280(AP_Baro &baro, AP_HAL::Device &dev) {24return probe(baro, dev, false);25}2627static AP_Baro_Backend *probe(AP_Baro &baro, AP_HAL::Device &dev, bool _is_dps310=false);2829protected:30bool init(bool _is_dps310);31bool read_calibration(void);32void timer(void);33void calculate_PT(int32_t UT, int32_t UP, float &pressure, float &temperature);3435void fix_config_bits16(int16_t &v, uint8_t bits) const;36void fix_config_bits32(int32_t &v, uint8_t bits) const;37void set_config_registers(void);38void check_health();3940AP_HAL::Device *dev;4142uint8_t instance;4344uint32_t count;45uint8_t err_count;46float pressure_sum;47float temperature_sum;48float last_temperature;49bool pending_reset;50bool is_dps310;5152struct dps280_cal {53int16_t C0; // 12bit54int16_t C1; // 12bit55int32_t C00; // 20bit56int32_t C10; // 20bit57int16_t C01; // 16bit58int16_t C11; // 16bit59int16_t C20; // 16bit60int16_t C21; // 16bit61int16_t C30; // 16bit62uint8_t temp_source;63} calibration;64};6566class AP_Baro_DPS310 : public AP_Baro_DPS280 {67// like DPS280 but workaround for temperature bug68public:69using AP_Baro_DPS280::AP_Baro_DPS280;70static AP_Baro_Backend *probe(AP_Baro &baro, AP_HAL::Device &dev);71};727374#endif // AP_BARO_DPS280_ENABLED757677