ardupilot/libraries/AP_Baro/AP_Baro_FBM320.h

57 lines
1.2 KiB
C
Raw Normal View History

2017-07-21 01:27:32 -03:00
#pragma once
#include "AP_Baro_Backend.h"
#ifndef AP_BARO_FBM320_ENABLED
#define AP_BARO_FBM320_ENABLED AP_BARO_BACKEND_DEFAULT_ENABLED
#endif
#if AP_BARO_FBM320_ENABLED
2017-07-21 01:27:32 -03:00
#include <AP_HAL/AP_HAL.h>
#include <AP_HAL/Device.h>
#include <AP_HAL/utility/OwnPtr.h>
#ifndef HAL_BARO_FBM320_I2C_ADDR
#define HAL_BARO_FBM320_I2C_ADDR 0x6C
#endif
#ifndef HAL_BARO_FBM320_I2C_ADDR2
#define HAL_BARO_FBM320_I2C_ADDR2 0x6D
#endif
2017-07-21 01:27:32 -03:00
class AP_Baro_FBM320 : public AP_Baro_Backend {
public:
AP_Baro_FBM320(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;
2017-07-21 01:27:32 -03:00
static AP_Baro_Backend *probe(AP_Baro &baro, AP_HAL::OwnPtr<AP_HAL::Device> dev);
private:
bool init(void);
bool read_calibration(void);
void timer(void);
void calculate_PT(int32_t UT, int32_t UP, int32_t &pressure, int32_t &temperature);
AP_HAL::OwnPtr<AP_HAL::Device> dev;
uint8_t instance;
uint32_t count;
float pressure_sum;
float temperature_sum;
uint8_t step;
int32_t value_T;
// Internal calibration registers
struct fbm320_calibration {
uint16_t C0, C1, C2, C3, C6, C8, C9, C10, C11, C12;
uint32_t C4, C5, C7;
} calibration;
};
#endif // AP_BARO_FBM320_ENABLED