PX4 Firmware
PX4 Autopilot Software http://px4.io
LPS22HB.hpp File Reference
#include <cstring>
#include <drivers/device/Device.hpp>
#include <drivers/device/i2c.h>
#include <drivers/device/spi.h>
#include <drivers/drv_baro.h>
#include <lib/cdev/CDev.hpp>
#include <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 dependency graph for LPS22HB.hpp:
This graph shows which files directly or indirectly include this file:

Go to the source code of this file.

Classes

class  LPS22HB
 

Macros

#define BOOT   (1 << 7)
 
#define FIFO_EN   (1 << 6)
 
#define STOP_ON_FTH   (1 << 5)
 
#define IF_ADD_INC   (1 << 4)
 
#define I2C_DIS   (1 << 3)
 
#define SWRESET   (1 << 2)
 
#define ONE_SHOT   (1 << 0)
 
#define T_OR   (1 << 5)
 
#define P_OR   (1 << 4)
 
#define T_DA   (1 << 1)
 
#define P_DA   (1 << 0)
 

Typedefs

typedef device::Device *(* LPS22HB_constructor) (int)
 

Functions

device::DeviceLPS22HB_SPI_interface (int bus)
 
device::DeviceLPS22HB_I2C_interface (int bus)
 

Variables

static constexpr uint8_t WHO_AM_I = 0x0F
 
static constexpr uint8_t LPS22HB_ID_WHO_AM_I = 0xB1
 
static constexpr uint8_t CTRL_REG1 = 0x10
 
static constexpr uint8_t CTRL_REG2 = 0x11
 
static constexpr uint8_t CTRL_REG3 = 0x12
 
static constexpr uint8_t STATUS = 0x27
 
static constexpr uint8_t PRESS_OUT_XL = 0x28
 
static constexpr uint8_t PRESS_OUT_L = 0x29
 
static constexpr uint8_t PRESS_OUT_H = 0x2A
 
static constexpr uint8_t TEMP_OUT_L = 0x2B
 
static constexpr uint8_t TEMP_OUT_H = 0x2C
 

Macro Definition Documentation

◆ BOOT

#define BOOT   (1 << 7)

Definition at line 57 of file LPS22HB.hpp.

Referenced by LPS22HB::reset(), and DfBebopBusWrapper::start().

◆ FIFO_EN

#define FIFO_EN   (1 << 6)

Definition at line 58 of file LPS22HB.hpp.

◆ I2C_DIS

#define I2C_DIS   (1 << 3)

Definition at line 61 of file LPS22HB.hpp.

◆ IF_ADD_INC

#define IF_ADD_INC   (1 << 4)

Definition at line 60 of file LPS22HB.hpp.

Referenced by LPS22HB::measure().

◆ ONE_SHOT

#define ONE_SHOT   (1 << 0)

Definition at line 63 of file LPS22HB.hpp.

Referenced by LPS22HB::measure().

◆ P_DA

#define P_DA   (1 << 0)

Definition at line 70 of file LPS22HB.hpp.

◆ P_OR

#define P_OR   (1 << 4)

Definition at line 68 of file LPS22HB.hpp.

◆ STOP_ON_FTH

#define STOP_ON_FTH   (1 << 5)

Definition at line 59 of file LPS22HB.hpp.

◆ SWRESET

#define SWRESET   (1 << 2)

Definition at line 62 of file LPS22HB.hpp.

Referenced by LPS22HB::reset().

◆ T_DA

#define T_DA   (1 << 1)

Definition at line 69 of file LPS22HB.hpp.

◆ T_OR

#define T_OR   (1 << 5)

Definition at line 67 of file LPS22HB.hpp.

Typedef Documentation

◆ LPS22HB_constructor

typedef device::Device*(* LPS22HB_constructor) (int)

Definition at line 82 of file LPS22HB.hpp.

Function Documentation

◆ LPS22HB_I2C_interface()

device::Device * LPS22HB_I2C_interface ( int  bus)

Definition at line 61 of file LPS22HB_I2C.cpp.

References LPS22HB_I2C::LPS22HB_I2C().

Here is the call graph for this function:

◆ LPS22HB_SPI_interface()

device::Device* LPS22HB_SPI_interface ( int  bus)

Variable Documentation

◆ CTRL_REG1

constexpr uint8_t CTRL_REG1 = 0x10
static

Definition at line 53 of file LPS22HB.hpp.

◆ CTRL_REG2

constexpr uint8_t CTRL_REG2 = 0x11
static

Definition at line 54 of file LPS22HB.hpp.

Referenced by LPS22HB::measure(), and LPS22HB::reset().

◆ CTRL_REG3

constexpr uint8_t CTRL_REG3 = 0x12
static

Definition at line 55 of file LPS22HB.hpp.

◆ LPS22HB_ID_WHO_AM_I

constexpr uint8_t LPS22HB_ID_WHO_AM_I = 0xB1
static

Definition at line 51 of file LPS22HB.hpp.

Referenced by LPS22HB_I2C::probe().

◆ PRESS_OUT_H

constexpr uint8_t PRESS_OUT_H = 0x2A
static

Definition at line 74 of file LPS22HB.hpp.

Referenced by LPS22HB::collect().

◆ PRESS_OUT_L

constexpr uint8_t PRESS_OUT_L = 0x29
static

Definition at line 73 of file LPS22HB.hpp.

Referenced by LPS22HB::collect().

◆ PRESS_OUT_XL

constexpr uint8_t PRESS_OUT_XL = 0x28
static

Definition at line 72 of file LPS22HB.hpp.

Referenced by LPS22HB::collect().

◆ STATUS

constexpr uint8_t STATUS = 0x27
static

Definition at line 65 of file LPS22HB.hpp.

Referenced by LPS22HB::collect().

◆ TEMP_OUT_H

constexpr uint8_t TEMP_OUT_H = 0x2C
static

Definition at line 77 of file LPS22HB.hpp.

Referenced by LPS22HB::collect().

◆ TEMP_OUT_L

constexpr uint8_t TEMP_OUT_L = 0x2B
static

Definition at line 76 of file LPS22HB.hpp.

Referenced by LPS22HB::collect().

◆ WHO_AM_I

constexpr uint8_t WHO_AM_I = 0x0F
static

Definition at line 50 of file LPS22HB.hpp.