ardupilot/libraries/AP_Baro/AP_Baro_BMP280.h

53 lines
1.1 KiB
C
Raw Permalink Normal View History

2016-12-29 10:45:02 -04:00
#pragma once
#include "AP_Baro_Backend.h"
#ifndef AP_BARO_BMP280_ENABLED
#define AP_BARO_BMP280_ENABLED AP_BARO_BACKEND_DEFAULT_ENABLED
#endif
#if AP_BARO_BMP280_ENABLED
2016-12-29 10:45:02 -04:00
#include <AP_HAL/AP_HAL.h>
#include <AP_HAL/Device.h>
#include <AP_HAL/utility/OwnPtr.h>
#ifndef HAL_BARO_BMP280_I2C_ADDR
#define HAL_BARO_BMP280_I2C_ADDR (0x76)
#endif
#ifndef HAL_BARO_BMP280_I2C_ADDR2
#define HAL_BARO_BMP280_I2C_ADDR2 (0x77)
#endif
2016-12-29 10:45:02 -04:00
class AP_Baro_BMP280 : public AP_Baro_Backend
{
public:
AP_Baro_BMP280(AP_Baro &baro, AP_HAL::OwnPtr<AP_HAL::Device> dev);
/* AP_Baro public interface: */
2018-11-07 08:11:28 -04:00
void update() override;
2016-12-29 10:45:02 -04:00
static AP_Baro_Backend *probe(AP_Baro &baro, AP_HAL::OwnPtr<AP_HAL::Device> dev);
private:
bool _init(void);
2017-01-13 21:53:48 -04:00
void _timer(void);
2016-12-29 10:45:02 -04:00
void _update_temperature(int32_t);
void _update_pressure(int32_t);
AP_HAL::OwnPtr<AP_HAL::Device> _dev;
uint8_t _instance;
int32_t _t_fine;
float _pressure_sum;
uint32_t _pressure_count;
2016-12-29 10:45:02 -04:00
float _temperature;
// Internal calibration registers
int16_t _t2, _t3, _p2, _p3, _p4, _p5, _p6, _p7, _p8, _p9;
uint16_t _t1, _p1;
};
#endif // AP_BARO_BMP280_ENABLED