Path: blob/master/libraries/AP_Baro/AP_Baro_BMP388.h
9794 views
#pragma once12#include "AP_Baro_Backend.h"34#if AP_BARO_BMP388_ENABLED56#include <AP_HAL/AP_HAL.h>7#include <AP_HAL/Device.h>89#ifndef HAL_BARO_BMP388_I2C_ADDR10#define HAL_BARO_BMP388_I2C_ADDR (0x76)11#endif12#ifndef HAL_BARO_BMP388_I2C_ADDR213#define HAL_BARO_BMP388_I2C_ADDR2 (0x77)14#endif1516class AP_Baro_BMP388 : public AP_Baro_Backend17{18public:19AP_Baro_BMP388(AP_Baro &baro, AP_HAL::Device &_dev);2021/* AP_Baro public interface: */22void update() override;2324static AP_Baro_Backend *probe(AP_Baro &baro, AP_HAL::Device &_dev);2526private:2728bool init(void);29void timer(void);30void update_temperature(uint32_t);31void update_pressure(uint32_t);3233AP_HAL::Device *dev;3435uint8_t instance;36float pressure_sum;37uint32_t pressure_count;38float temperature;3940// Internal calibration registers41struct PACKED {42int16_t nvm_par_p1; // at 0x3643int16_t nvm_par_p2;44int8_t nvm_par_p3;45int8_t nvm_par_p4;46int16_t nvm_par_p5;47int16_t nvm_par_p6;48int8_t nvm_par_p7;49int8_t nvm_par_p8;50int16_t nvm_par_p9;51int8_t nvm_par_p10;52int8_t nvm_par_p11;53} calib_p;5455struct PACKED {56uint16_t nvm_par_t1; // at 0x3157uint16_t nvm_par_t2;58int8_t nvm_par_t3;59} calib_t;6061// scaled calibration data62struct {63float par_t1;64float par_t2;65float par_t3;66float par_p1;67float par_p2;68float par_p3;69float par_p4;70float par_p5;71float par_p6;72float par_p7;73float par_p8;74float par_p9;75float par_p10;76float par_p11;77float t_lin;78} calib;7980void scale_calibration_data(void);81bool read_registers(uint8_t reg, uint8_t *data, uint8_t len);82};8384#endif // AP_BARO_BMP388_ENABLED858687