APM:Libraries
AP_Airspeed_MS5525.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 /*
17  backend driver for airspeed from a I2C MS5525D0 sensor
18  */
19 #include "AP_Airspeed_MS5525.h"
20 
21 #include <stdio.h>
22 #include <utility>
23 
24 #include <AP_Common/AP_Common.h>
25 #include <AP_HAL/AP_HAL.h>
26 #include <AP_HAL/I2CDevice.h>
28 #include <AP_Math/AP_Math.h>
29 
30 extern const AP_HAL::HAL &hal;
31 
32 #define MS5525D0_I2C_ADDR_1 0x76
33 #define MS5525D0_I2C_ADDR_2 0x77
34 
35 #define REG_RESET 0x1E
36 #define REG_CONVERT_D1_OSR_256 0x40
37 #define REG_CONVERT_D1_OSR_512 0x42
38 #define REG_CONVERT_D1_OSR_1024 0x44
39 #define REG_CONVERT_D1_OSR_2048 0x46
40 #define REG_CONVERT_D1_OSR_4096 0x48
41 #define REG_CONVERT_D2_OSR_256 0x50
42 #define REG_CONVERT_D2_OSR_512 0x52
43 #define REG_CONVERT_D2_OSR_1024 0x54
44 #define REG_CONVERT_D2_OSR_2048 0x56
45 #define REG_CONVERT_D2_OSR_4096 0x58
46 #define REG_ADC_READ 0x00
47 #define REG_PROM_BASE 0xA0
48 
49 // go for 1024 oversampling. This should be fast enough to reduce
50 // noise but low enough to keep self-heating small
51 #define REG_CONVERT_PRESSURE REG_CONVERT_D1_OSR_1024
52 #define REG_CONVERT_TEMPERATURE REG_CONVERT_D2_OSR_1024
53 
54 AP_Airspeed_MS5525::AP_Airspeed_MS5525(AP_Airspeed &_frontend, uint8_t _instance, MS5525_ADDR address) :
55  AP_Airspeed_Backend(_frontend, _instance)
56 {
57  _address = address;
58 }
59 
60 // probe and initialise the sensor
62 {
63  const uint8_t addresses[] = { MS5525D0_I2C_ADDR_1, MS5525D0_I2C_ADDR_2 };
64  bool found = false;
65  for (uint8_t i=0; i<ARRAY_SIZE(addresses); i++) {
66  if (_address != MS5525_ADDR_AUTO && i != (uint8_t)_address) {
67  continue;
68  }
69  dev = hal.i2c_mgr->get_device(get_bus(), addresses[i]);
70  if (!dev) {
71  continue;
72  }
74  continue;
75  }
76 
77  // lots of retries during probe
78  dev->set_retries(5);
79 
80  found = read_prom();
81 
82  if (found) {
83  printf("MS5525: Found sensor on bus %u address 0x%02x\n", get_bus(), addresses[i]);
84  break;
85  }
86  dev->get_semaphore()->give();
87  }
88  if (!found) {
89  printf("MS5525: no sensor found\n");
90  return false;
91  }
92 
93  // Send a command to read temperature first
94  uint8_t reg = REG_CONVERT_TEMPERATURE;
95  dev->transfer(&reg, 1, nullptr, 0);
96  state = 0;
98 
99  // drop to 2 retries for runtime
100  dev->set_retries(2);
101 
102  dev->get_semaphore()->give();
103 
104  // read at 80Hz
105  dev->register_periodic_callback(1000000UL/80U,
107  return true;
108 }
109 
110 
115 {
116  uint16_t n_rem = 0;
117  uint8_t n_bit;
118 
119  for (uint8_t cnt = 0; cnt < sizeof(prom); cnt++) {
120  /* uneven bytes */
121  if (cnt & 1) {
122  n_rem ^= (uint8_t)((prom[cnt >> 1]) & 0x00FF);
123  } else {
124  n_rem ^= (uint8_t)(prom[cnt >> 1] >> 8);
125  }
126 
127  for (n_bit = 8; n_bit > 0; n_bit--) {
128  if (n_rem & 0x8000) {
129  n_rem = (n_rem << 1) ^ 0x3000;
130  } else {
131  n_rem = (n_rem << 1);
132  }
133  }
134  }
135 
136  return (n_rem >> 12) & 0xF;
137 }
138 
140 {
141  // reset the chip to ensure it has correct prom values loaded
142  uint8_t reg = REG_RESET;
143  if (!dev->transfer(&reg, 1, nullptr, 0)) {
144  return false;
145  }
146  hal.scheduler->delay(5);
147 
148  bool all_zero = true;
149  for (uint8_t i = 0; i < 8; i++) {
150  be16_t val;
151  if (!dev->read_registers(REG_PROM_BASE+i*2, (uint8_t *) &val,
152  sizeof(uint16_t))) {
153  return false;
154  }
155  prom[i] = be16toh(val);
156  if (prom[i] != 0) {
157  all_zero = false;
158  }
159  }
160 
161  if (all_zero) {
162  return false;
163  }
164 
165  /* save the read crc */
166  const uint16_t crc_read = prom[7] & 0xf;
167 
168  /* remove CRC byte */
169  prom[7] &= 0xff00;
170 
171  uint16_t crc_calc = crc4_prom();
172  if (crc_read != crc_calc) {
173  printf("MS5525: CRC mismatch 0x%04x 0x%04x\n", crc_read, crc_calc);
174  }
175  return crc_read == crc_calc;
176 }
177 
178 
179 /*
180  read from the ADC
181  */
183 {
184  uint8_t val[3];
185  if (!dev->read_registers(REG_ADC_READ, val, 3)) {
186  return 0;
187  }
188  return (val[0] << 16) | (val[1] << 8) | val[2];
189 }
190 
191 /*
192  calculate pressure and temperature
193  */
195 {
196  // table for the 001DS part, 1PSI range
197  const uint8_t Q1 = 15;
198  const uint8_t Q2 = 17;
199  const uint8_t Q3 = 7;
200  const uint8_t Q4 = 5;
201  const uint8_t Q5 = 7;
202  const uint8_t Q6 = 21;
203 
204  int64_t dT = D2 - int64_t(prom[5]) * (1UL<<Q5);
205  int64_t TEMP = 2000 + (dT*int64_t(prom[6]))/(1UL<<Q6);
206  int64_t OFF = int64_t(prom[2])*(1UL<<Q2) + (int64_t(prom[4])*dT)/(1UL<<Q4);
207  int64_t SENS = int64_t(prom[1])*(1UL<<Q1) + (int64_t(prom[3])*dT)/(1UL<<Q3);
208  int64_t P = (D1*SENS/(1UL<<21)-OFF)/(1UL<<15);
209  const float PSI_to_Pa = 6894.757f;
210  float P_Pa = PSI_to_Pa * 1.0e-4 * P;
211  float Temp_C = TEMP * 0.01;
212 
213 #if 0
214  static uint16_t counter;
215  if (counter++ == 100) {
216  printf("P=%.6f T=%.2f D1=%d D2=%d\n", P_Pa, Temp_C, D1, D2);
217  counter=0;
218  }
219 #endif
220 
222  pressure_sum += P_Pa;
223  temperature_sum += Temp_C;
224  press_count++;
225  temp_count++;
227  sem->give();
228  }
229 }
230 
231 // 50Hz timer
233 {
234  if (AP_HAL::micros() - command_send_us < 10000) {
235  // we should avoid trying to read the ADC too soon after
236  // sending the command
237  return;
238  }
239 
240  uint32_t adc_val = read_adc();
241 
242  if (adc_val == 0) {
243  // we have either done a read too soon after sending the
244  // request or we have tried to read the same sample twice. We
245  // re-send the command now as we don't know what state the
246  // sensor is in, and we do want to trigger it sending a value,
247  // which we will discard
248  if (dev->transfer(&cmd_sent, 1, nullptr, 0)) {
250  }
251  // when we get adc_val == 0 then then both the current value and
252  // the next value we read from the sensor are invalid
253  ignore_next = true;
254  return;
255  }
256 
257  /*
258  * If read fails, re-initiate a read command for current state or we are
259  * stuck
260  */
261  if (!ignore_next) {
263  D2 = adc_val;
264  } else if (cmd_sent == REG_CONVERT_PRESSURE) {
265  D1 = adc_val;
266  calculate();
267  }
268  }
269 
270  ignore_next = false;
271 
273  if (!dev->transfer(&cmd_sent, 1, nullptr, 0)) {
274  // we don't know for sure what state the sensor is in when we
275  // fail to send the command, so ignore the next response
276  ignore_next = true;
277  return;
278  }
280 
281  state = (state + 1) % 5;
282 }
283 
284 // return the current differential_pressure in Pascal
286 {
287  if ((AP_HAL::millis() - last_sample_time_ms) > 100) {
288  return false;
289  }
291  if (press_count > 0) {
293  press_count = 0;
294  pressure_sum = 0;
295  }
296  sem->give();
297  }
298  _pressure = pressure;
299  return true;
300 }
301 
302 // return the current temperature in degrees C, if available
303 bool AP_Airspeed_MS5525::get_temperature(float &_temperature)
304 {
305  if ((AP_HAL::millis() - last_sample_time_ms) > 100) {
306  return false;
307  }
309  if (temp_count > 0) {
311  temp_count = 0;
312  temperature_sum = 0;
313  }
314  sem->give();
315  }
316  _temperature = temperature;
317  return true;
318 }
AP_HAL::OwnPtr< AP_HAL::I2CDevice > dev
int printf(const char *fmt,...)
Definition: stdio.c:113
static uint8_t counter
virtual Device::PeriodicHandle register_periodic_callback(uint32_t period_usec, Device::PeriodicCb) override=0
#define REG_CONVERT_TEMPERATURE
#define REG_RESET
virtual void set_retries(uint8_t retries)
Definition: Device.h:260
virtual Semaphore * get_semaphore() override=0
#define REG_CONVERT_PRESSURE
#define HAL_SEMAPHORE_BLOCK_FOREVER
Definition: Semaphores.h:5
virtual bool take(uint32_t timeout_ms) WARN_IF_UNUSED=0
const AP_HAL::HAL & hal
Definition: AC_PID_test.cpp:14
bool get_temperature(float &temperature) override
AP_HAL::Semaphore * sem
virtual void delay(uint16_t ms)=0
#define MS5525D0_I2C_ADDR_1
static uint16_t be16toh(be16_t value)
Definition: sparse-endian.h:83
uint32_t millis()
Definition: system.cpp:157
virtual bool transfer(const uint8_t *send, uint32_t send_len, uint8_t *recv, uint32_t recv_len) override=0
#define MS5525D0_I2C_ADDR_2
virtual bool give()=0
#define ARRAY_SIZE(_arr)
Definition: AP_Common.h:80
AP_HAL::I2CDeviceManager * i2c_mgr
Definition: HAL.h:106
Common definitions and utility routines for the ArduPilot libraries.
bool get_differential_pressure(float &pressure) override
uint8_t get_bus(void) const
bool read_registers(uint8_t first_reg, uint8_t *recv, uint32_t recv_len)
Definition: Device.h:113
#define FUNCTOR_BIND_MEMBER(func, rettype,...)
Definition: functor.h:31
AP_Airspeed_MS5525(AP_Airspeed &frontend, uint8_t _instance, MS5525_ADDR address)
virtual OwnPtr< AP_HAL::I2CDevice > get_device(uint8_t bus, uint8_t address, uint32_t bus_clock=400000, bool use_smbus=false, uint32_t timeout_ms=4)=0
#define REG_ADC_READ
uint32_t micros()
Definition: system.cpp:152
AP_HAL::Scheduler * scheduler
Definition: HAL.h:114
uint16_t __ap_bitwise be16_t
Definition: sparse-endian.h:36
#define REG_PROM_BASE