51 #include <px4_platform_common/getopt.h> 52 #include <px4_platform_common/px4_work_queue/ScheduledWorkItem.hpp> 56 #include "board_config.h" 58 #define ADDR_RESET_CMD 0x1E 59 #define ADDR_PROM_SETUP 0xA0 63 #define IOCTL_MEASURE 3 92 extern bool crc4(uint16_t *n_prom);
uint16_t c1_pressure_sens
bool crc4(uint16_t *n_prom)
MS5611 crc4 cribbed from the datasheet.
API for the uORB lightweight object broker.
Calibration PROM as reported by the device.
uint16_t c4_temp_coeff_pres_offset
device::Device * MS5611_i2c_interface(ms5611::prom_u &prom_buf, uint8_t busnum)
uint16_t c5_reference_temp
Simple error/warning functions, heavily inspired by the BSD functions of the same names...
uint16_t c2_pressure_offset
uint16_t c6_temp_coeff_temp
device::Device * MS5611_sim_interface(ms5611::prom_u &prom_buf, uint8_t busnum)
Local functions in support of the shell command.
device::Device * MS5611_spi_interface(ms5611::prom_u &prom_buf, uint8_t busnum)
Fundamental base class for all physical drivers (I2C, SPI).
uint16_t c3_temp_coeff_pres_sens
Barometric pressure sensor driver interface.
Performance measuring tools.
Base class for devices connected via I2C.