32 #define MS5525D0_I2C_ADDR_1 0x76 33 #define MS5525D0_I2C_ADDR_2 0x77 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 51 #define REG_CONVERT_PRESSURE REG_CONVERT_D1_OSR_1024 52 #define REG_CONVERT_TEMPERATURE REG_CONVERT_D2_OSR_1024 65 for (uint8_t i=0; i<
ARRAY_SIZE(addresses); i++) {
83 printf(
"MS5525: Found sensor on bus %u address 0x%02x\n",
get_bus(), addresses[i]);
89 printf(
"MS5525: no sensor found\n");
119 for (uint8_t cnt = 0; cnt <
sizeof(
prom); cnt++) {
122 n_rem ^= (uint8_t)((
prom[cnt >> 1]) & 0x00FF);
124 n_rem ^= (uint8_t)(
prom[cnt >> 1] >> 8);
127 for (n_bit = 8; n_bit > 0; n_bit--) {
128 if (n_rem & 0x8000) {
129 n_rem = (n_rem << 1) ^ 0x3000;
131 n_rem = (n_rem << 1);
136 return (n_rem >> 12) & 0xF;
148 bool all_zero =
true;
149 for (uint8_t i = 0; i < 8; i++) {
166 const uint16_t crc_read =
prom[7] & 0xf;
172 if (crc_read != crc_calc) {
173 printf(
"MS5525: CRC mismatch 0x%04x 0x%04x\n", crc_read, crc_calc);
175 return crc_read == crc_calc;
188 return (val[0] << 16) | (val[1] << 8) | val[2];
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;
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;
215 if (counter++ == 100) {
216 printf(
"P=%.6f T=%.2f D1=%d D2=%d\n", P_Pa, Temp_C,
D1,
D2);
AP_HAL::OwnPtr< AP_HAL::I2CDevice > dev
int printf(const char *fmt,...)
virtual Device::PeriodicHandle register_periodic_callback(uint32_t period_usec, Device::PeriodicCb) override=0
#define REG_CONVERT_TEMPERATURE
virtual void set_retries(uint8_t retries)
virtual Semaphore * get_semaphore() override=0
#define REG_CONVERT_PRESSURE
#define HAL_SEMAPHORE_BLOCK_FOREVER
virtual bool take(uint32_t timeout_ms) WARN_IF_UNUSED=0
bool get_temperature(float &temperature) override
virtual void delay(uint16_t ms)=0
#define MS5525D0_I2C_ADDR_1
static uint16_t be16toh(be16_t value)
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
uint32_t last_sample_time_ms
AP_HAL::I2CDeviceManager * i2c_mgr
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)
#define FUNCTOR_BIND_MEMBER(func, rettype,...)
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
AP_HAL::Scheduler * scheduler
uint16_t __ap_bitwise be16_t