APM:Libraries
AP_Baro_DPS280.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, float &pressure, float &temperature);
23 
24  void fix_config_bits16(int16_t &v, uint8_t bits) const;
25  void fix_config_bits32(int32_t &v, uint8_t bits) const;
26 
28 
29  uint8_t instance;
30 
31  uint32_t count;
32  float pressure_sum;
34 
35  struct dps280_cal {
36  int16_t C0; // 12bit
37  int16_t C1; // 12bit
38  int32_t C00; // 20bit
39  int32_t C10; // 20bit
40  int16_t C01; // 16bit
41  int16_t C11; // 16bit
42  int16_t C20; // 16bit
43  int16_t C21; // 16bit
44  int16_t C30; // 16bit
45  uint8_t temp_source;
46  } calibration;
47 };
void fix_config_bits16(int16_t &v, uint8_t bits) const
struct AP_Baro_DPS280::dps280_cal calibration
static AP_Baro_Backend * probe(AP_Baro &baro, AP_HAL::OwnPtr< AP_HAL::Device > dev)
AP_HAL::OwnPtr< AP_HAL::Device > dev
float temperature
Definition: Airspeed.cpp:32
static AP_Baro baro
Definition: ModuleTest.cpp:18
float v
Definition: Printf.cpp:15
bool read_calibration(void)
AP_Baro_DPS280(AP_Baro &baro, AP_HAL::OwnPtr< AP_HAL::Device > dev)
void fix_config_bits32(int32_t &v, uint8_t bits) const
void calculate_PT(int32_t UT, int32_t UP, float &pressure, float &temperature)