APM:Libraries
AP_Baro_FBM320.h
Go to the documentation of this file.
1 #pragma once
2 
3 #include <AP_HAL/AP_HAL.h>
4 #include <AP_HAL/Device.h>
6 
7 #include "AP_Baro_Backend.h"
8 
10 public:
12 
13  /* AP_Baro public interface: */
14  void update();
15 
17 
18 private:
19  bool init(void);
20  bool read_calibration(void);
21  void timer(void);
22  void calculate_PT(int32_t UT, int32_t UP, int32_t &pressure, int32_t &temperature);
23 
25 
26  uint8_t instance;
27 
28  uint32_t count;
29  float pressure_sum;
31  uint8_t step;
32 
33  int32_t value_T;
34 
35  // Internal calibration registers
37  uint16_t C0, C1, C2, C3, C6, C8, C9, C10, C11, C12;
38  uint32_t C4, C5, C7;
39  } calibration;
40 };
struct AP_Baro_FBM320::fbm320_calibration calibration
static AP_Baro_Backend * probe(AP_Baro &baro, AP_HAL::OwnPtr< AP_HAL::Device > dev)
bool read_calibration(void)
float temperature
Definition: Airspeed.cpp:32
AP_HAL::OwnPtr< AP_HAL::Device > dev
AP_Baro_FBM320(AP_Baro &baro, AP_HAL::OwnPtr< AP_HAL::Device > dev)
static AP_Baro baro
Definition: ModuleTest.cpp:18
void calculate_PT(int32_t UT, int32_t UP, int32_t &pressure, int32_t &temperature)