APM:Libraries
AP_Baro_DPS280.cpp
Go to the documentation of this file.
1 /*
2  This program is free software: you can redistribute it and/or modify
3  it under the terms of the GNU General Public License as published by
4  the Free Software Foundation, either version 3 of the License, or
5  (at your option) any later version.
6 
7  This program is distributed in the hope that it will be useful,
8  but WITHOUT ANY WARRANTY; without even the implied warranty of
9  MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
10  GNU General Public License for more details.
11 
12  You should have received a copy of the GNU General Public License
13  along with this program. If not, see <http://www.gnu.org/licenses/>.
14  */
15 /*
16  DPS280 barometer driver
17  */
18 
19 #include "AP_Baro_DPS280.h"
20 
21 #include <utility>
22 #include <stdio.h>
23 
24 extern const AP_HAL::HAL &hal;
25 
26 #define DPS280_REG_PRESS 0x00
27 #define DPS280_REG_TEMP 0x03
28 #define DPS280_REG_PCONF 0x06
29 #define DPS280_REG_TCONF 0x07
30 #define DPS280_REG_MCONF 0x08
31 #define DPS280_REG_CREG 0x09
32 #define DPS280_REG_ISTS 0x0A
33 #define DPS280_REG_FSTS 0x0B
34 #define DPS280_REG_RESET 0x0C
35 #define DPS280_REG_PID 0x0D
36 #define DPS280_REG_COEF 0x10
37 #define DPS280_REG_CSRC 0x28
38 
39 #define DPS280_WHOAMI 0x10
40 
41 
43  : AP_Baro_Backend(baro)
44  , dev(std::move(_dev))
45 {
46 }
47 
50 {
51  if (!_dev) {
52  return nullptr;
53  }
54 
55  AP_Baro_DPS280 *sensor = new AP_Baro_DPS280(baro, std::move(_dev));
56  if (!sensor || !sensor->init()) {
57  delete sensor;
58  return nullptr;
59  }
60  return sensor;
61 }
62 
63 /*
64  handle bit width for 16 bit config registers
65  */
66 void AP_Baro_DPS280::fix_config_bits16(int16_t &v, uint8_t bits) const
67 {
68  if (v > int16_t((1U<<(bits-1))-1)) {
69  v = v - (1U<<bits);
70  }
71 }
72 
73 /*
74  handle bit width for 32 bit config registers
75  */
76 void AP_Baro_DPS280::fix_config_bits32(int32_t &v, uint8_t bits) const
77 {
78  if (v > int32_t((1U<<(bits-1))-1)) {
79  v = v - (1U<<bits);
80  }
81 }
82 
83 /*
84  read calibration data
85  */
87 {
88  uint8_t buf[18];
89 
90  if (!dev->read_registers(DPS280_REG_COEF, buf, 18)) {
91  return false;
92  }
93 
94  calibration.C0 = (buf[0] << 4) + ((buf[1] >>4) & 0x0F);
95  calibration.C1 = (buf[2] + ((buf[1] & 0x0F)<<8));
96  calibration.C00 = ((buf[4]<<4) + (buf[3]<<12)) + ((buf[5]>>4) & 0x0F);
97  calibration.C10 = ((buf[5] & 0x0F)<<16) + buf[7] + (buf[6]<<8);
98  calibration.C01 = (buf[9] + (buf[8]<<8));
99  calibration.C11 = (buf[11] + (buf[10]<<8));
100  calibration.C20 = (buf[13] + (buf[12]<<8));
101  calibration.C21 = (buf[15] + (buf[14]<<8));
102  calibration.C30 = (buf[17] + (buf[16]<<8));
103 
113 
114  /* get calibration source */
116  return false;
117  }
118  calibration.temp_source &= 0x80;
119 
120  return true;
121 }
122 
124 {
126  return false;
127  }
128 
130 
131  uint8_t whoami=0;
132  if (!dev->read_registers(DPS280_REG_PID, &whoami, 1) ||
133  whoami != DPS280_WHOAMI) {
134  // not a DPS280
135  printf("DPS280 whoami=0x%x\n", whoami);
136  dev->get_semaphore()->give();
137  return false;
138  }
139 
140  if (!read_calibration()) {
141  dev->get_semaphore()->give();
142  return false;
143  }
144 
145  dev->write_register(DPS280_REG_CREG, 0x0C); // shift for 16x oversampling
146  dev->write_register(DPS280_REG_PCONF, 0x54); // 32 Hz, 16x oversample
147  dev->write_register(DPS280_REG_TCONF, 0x54 | calibration.temp_source); // 32 Hz, 16x oversample
148  dev->write_register(DPS280_REG_MCONF, 0x07); // continuous temp and pressure
149 
151 
152  dev->get_semaphore()->give();
153 
154  // request 64Hz update. New data will be available at 32Hz
156 
157  return true;
158 }
159 
160 /*
161  calculate corrected pressure and temperature
162  */
163 void AP_Baro_DPS280::calculate_PT(int32_t UT, int32_t UP, float &pressure, float &temperature)
164 {
165  const struct dps280_cal &cal = calibration;
166  // scaling for 16x oversampling
167  const float scaling_16 = 1.0/253952;
168 
169  float temp_scaled;
170  float press_scaled;
171 
172  temp_scaled = float(UT) * scaling_16;
173  temperature = cal.C0 * 0.5 + cal.C1 * temp_scaled;
174 
175  press_scaled = float(UP) * scaling_16;
176 
177  pressure = cal.C00;
178  pressure += press_scaled * (cal.C10 + press_scaled * (cal.C20 + press_scaled * cal.C30));
179  pressure += temp_scaled * cal.C01;
180  pressure += temp_scaled * press_scaled * (cal.C11 + press_scaled * cal.C21);
181 }
182 
183 // acumulate a new sensor reading
185 {
186  uint8_t buf[6];
187  uint8_t ready;
188 
189  if (!dev->read_registers(DPS280_REG_MCONF, &ready, 1) || !(ready & (1U<<4))) {
190  // pressure not ready
191  return;
192  }
193  if (!dev->read_registers(DPS280_REG_PRESS, buf, 3)) {
194  return;
195  }
196  if (!dev->read_registers(DPS280_REG_TEMP, &buf[3], 3)) {
197  return;
198  }
199 
200  int32_t press = (buf[2]) + (buf[1]<<8) + (buf[0]<<16);
201  int32_t temp = (buf[5]) + (buf[4]<<8) + (buf[3]<<16);
202  fix_config_bits32(press, 24);
203  fix_config_bits32(temp, 24);
204 
205  float pressure, temperature;
206 
207  calculate_PT(temp, press, pressure, temperature);
208 
209  if (!pressure_ok(pressure)) {
210  return;
211  }
212 
213  if (_sem->take_nonblocking()) {
214  pressure_sum += pressure;
216  count++;
217  _sem->give();
218  }
219 }
220 
221 // transfer data to the frontend
223 {
224  if (count != 0 && _sem->take_nonblocking()) {
225  if (count == 0) {
226  _sem->give();
227  return;
228  }
229 
231  pressure_sum = 0;
232  temperature_sum = 0;
233  count=0;
234 
235  _sem->give();
236  }
237 }
int printf(const char *fmt,...)
Definition: stdio.c:113
#define AP_USEC_PER_MSEC
Definition: definitions.h:93
#define DPS280_WHOAMI
void fix_config_bits16(int16_t &v, uint8_t bits) const
const AP_HAL::HAL & hal
Definition: AC_PID_test.cpp:14
virtual PeriodicHandle register_periodic_callback(uint32_t period_usec, PeriodicCb)=0
void _copy_to_frontend(uint8_t instance, float pressure, float temperature)
uint8_t register_sensor(void)
Definition: AP_Baro.cpp:705
AP_HAL::Semaphore * _sem
virtual AP_HAL::Semaphore * get_semaphore()=0
#define HAL_SEMAPHORE_BLOCK_FOREVER
Definition: Semaphores.h:5
virtual bool take(uint32_t timeout_ms) WARN_IF_UNUSED=0
struct AP_Baro_DPS280::dps280_cal calibration
static AP_Baro_Backend * probe(AP_Baro &baro, AP_HAL::OwnPtr< AP_HAL::Device > dev)
#define DPS280_REG_CREG
AP_HAL::OwnPtr< AP_HAL::Device > dev
#define DPS280_REG_COEF
float temperature
Definition: Airspeed.cpp:32
#define DPS280_REG_TCONF
virtual bool take_nonblocking() WARN_IF_UNUSED=0
AP_Baro & _frontend
static AP_HAL::OwnPtr< AP_HAL::Device > dev
Definition: ICM20789.cpp:16
#define DPS280_REG_PRESS
virtual bool set_speed(Speed speed)=0
static AP_Baro baro
Definition: ModuleTest.cpp:18
bool pressure_ok(float press)
virtual bool give()=0
float v
Definition: Printf.cpp:15
bool read_calibration(void)
#define DPS280_REG_PCONF
AP_Baro_DPS280(AP_Baro &baro, AP_HAL::OwnPtr< AP_HAL::Device > dev)
#define DPS280_REG_MCONF
bool read_registers(uint8_t first_reg, uint8_t *recv, uint32_t recv_len)
Definition: Device.h:113
void fix_config_bits32(int32_t &v, uint8_t bits) const
#define FUNCTOR_BIND_MEMBER(func, rettype,...)
Definition: functor.h:31
#define DPS280_REG_CSRC
#define DPS280_REG_PID
#define DPS280_REG_TEMP
bool write_register(uint8_t reg, uint8_t val, bool checked=false)
Definition: Device.h:125
void calculate_PT(int32_t UT, int32_t UP, float &pressure, float &temperature)