44 #include <px4_platform_common/getopt.h> 45 #include <px4_platform_common/px4_work_queue/ScheduledWorkItem.hpp> 58 #define FIFO_EN (1 << 6) 59 #define STOP_ON_FTH (1 << 5) 60 #define IF_ADD_INC (1 << 4) 61 #define I2C_DIS (1 << 3) 62 #define SWRESET (1 << 2) 63 #define ONE_SHOT (1 << 0) 65 static constexpr uint8_t
STATUS = 0x27;
67 #define T_OR (1 << 5) // Temperature data overrun. 68 #define P_OR (1 << 4) // Pressure data overrun. 69 #define T_DA (1 << 1) // Temperature data available. 70 #define P_DA (1 << 0) // Pressure data available. 92 virtual int ioctl(
struct file *filp,
int cmd,
unsigned long arg);
166 int read_reg(uint8_t reg, uint8_t &val);
int reset()
Reset the device.
static constexpr uint8_t LPS22HB_ID_WHO_AM_I
int measure()
Issue a measurement command.
API for the uORB lightweight object broker.
static constexpr uint8_t PRESS_OUT_XL
static constexpr uint8_t TEMP_OUT_H
unsigned _measure_interval
device::Device * _interface
static constexpr uint8_t PRESS_OUT_L
void start()
Initialise the automatic measurement state machine and start it.
sensor_baro_s _last_report
used for info()
static constexpr uint8_t CTRL_REG2
void Run() override
Perform a poll cycle; collect from the previous measurement and start a new one.
perf_counter_t _sample_perf
static constexpr uint8_t STATUS
Definitions for the generic base classes in the device framework.
virtual int ioctl(struct file *filp, int cmd, unsigned long arg)
device::Device * LPS22HB_I2C_interface(int bus)
Abstract class for any character device.
static constexpr uint8_t TEMP_OUT_L
Simple error/warning functions, heavily inspired by the BSD functions of the same names...
static constexpr uint8_t CTRL_REG1
perf_counter_t _comms_errors
device::Device * LPS22HB_SPI_interface(int bus)
void print_info()
Diagnostics - print some basic information about the driver.
static constexpr uint8_t CTRL_REG3
__BEGIN_DECLS typedef void * orb_advert_t
ORB topic advertiser handle.
int collect()
Collect the result of the most recent measurement.
static constexpr uint8_t PRESS_OUT_H
LPS22HB(device::Device *interface, const char *path)
struct @83::@85::@87 file
int write_reg(uint8_t reg, uint8_t val)
Write a register.
LPS22HB operator=(const LPS22HB &)
Fundamental base class for all physical drivers (I2C, SPI).
void stop()
Stop the automatic measurement state machine.
Barometric pressure sensor driver interface.
static constexpr uint8_t WHO_AM_I
Performance measuring tools.
int read_reg(uint8_t reg, uint8_t &val)
Read a register.
Base class for devices connected via I2C.