| PX4 Firmware
    PX4 Autopilot Software http://px4.io | 
Shared defines for the ms5611 driver. More...
#include <string.h>#include <drivers/device/i2c.h>#include <drivers/device/device.h>#include <drivers/device/ringbuffer.h>#include <drivers/device/spi.h>#include <drivers/drv_baro.h>#include <lib/cdev/CDev.hpp>#include <lib/perf/perf_counter.h>#include <px4_platform_common/getopt.h>#include <px4_platform_common/px4_work_queue/ScheduledWorkItem.hpp>#include <systemlib/err.h>#include <uORB/uORB.h>#include "board_config.h"Go to the source code of this file.
| Classes | |
| struct | ms5611::prom_s | 
| Calibration PROM as reported by the device.  More... | |
| union | ms5611::prom_u | 
| Grody hack for crc4()  More... | |
| Namespaces | |
| ms5611 | |
| Local functions in support of the shell command. | |
| Macros | |
| #define | ADDR_RESET_CMD 0x1E /* write to this address to reset chip */ | 
| #define | ADDR_PROM_SETUP 0xA0 /* address of 8x 2 bytes factory and calibration data */ | 
| #define | IOCTL_RESET 2 | 
| #define | IOCTL_MEASURE 3 | 
| Typedefs | |
| typedef device::Device *(* | MS5611_constructor) (ms5611::prom_u &prom_buf, uint8_t busnum) | 
| Functions | |
| bool | ms5611::crc4 (uint16_t *n_prom) | 
| MS5611 crc4 cribbed from the datasheet.  More... | |
| device::Device * | MS5611_spi_interface (ms5611::prom_u &prom_buf, uint8_t busnum) | 
| device::Device * | MS5611_i2c_interface (ms5611::prom_u &prom_buf, uint8_t busnum) | 
| device::Device * | MS5611_sim_interface (ms5611::prom_u &prom_buf, uint8_t busnum) | 
| #define ADDR_PROM_SETUP 0xA0 /* address of 8x 2 bytes factory and calibration data */ | 
Definition at line 59 of file ms5611.h.
Referenced by MS5611_I2C::_read_prom().
| #define ADDR_RESET_CMD 0x1E /* write to this address to reset chip */ | 
Definition at line 58 of file ms5611.h.
Referenced by MS5611_I2C::_reset().
| typedef device::Device*(* MS5611_constructor) (ms5611::prom_u &prom_buf, uint8_t busnum) | 
| device::Device* MS5611_i2c_interface | ( | ms5611::prom_u & | prom_buf, | 
| uint8_t | busnum | ||
| ) | 
Definition at line 90 of file ms5611_i2c.cpp.
References MS5611_I2C::MS5611_I2C().
| device::Device* MS5611_sim_interface | ( | ms5611::prom_u & | prom_buf, | 
| uint8_t | busnum | ||
| ) | 
| device::Device* MS5611_spi_interface | ( | ms5611::prom_u & | prom_buf, | 
| uint8_t | busnum | ||
| ) |