PX4 Firmware
PX4 Autopilot Software http://px4.io
|
Shared defines for the bmp388 driver. More...
#include <math.h>
#include <drivers/drv_baro.h>
#include <drivers/drv_hrt.h>
#include <lib/cdev/CDev.hpp>
#include <perf/perf_counter.h>
#include <px4_platform_common/px4_work_queue/ScheduledWorkItem.hpp>
#include <lib/drivers/barometer/PX4Barometer.hpp>
#include "board_config.h"
Go to the source code of this file.
Classes | |
struct | calibration_s |
struct | data_s |
struct | bmp3_reg_calib_data |
struct | bmp3_data |
struct | bmp3_calib_data |
struct | bmp3_uncomp_data |
struct | fcalibration_s |
class | IBMP388 |
class | BMP388 |
Macros | |
#define | BMP3_CHIP_ID (0x50) |
#define | BMP3_NO_OVERSAMPLING (0x00) |
#define | BMP3_OVERSAMPLING_2X (0x01) |
#define | BMP3_OVERSAMPLING_4X (0x02) |
#define | BMP3_OVERSAMPLING_8X (0x03) |
#define | BMP3_OVERSAMPLING_16X (0x04) |
#define | BMP3_OVERSAMPLING_32X (0x05) |
#define | BMP3_IIR_FILTER_DISABLE (0x00) |
#define | BMP3_IIR_FILTER_COEFF_1 (0x01) |
#define | BMP3_IIR_FILTER_COEFF_3 (0x02) |
#define | BMP3_IIR_FILTER_COEFF_7 (0x03) |
#define | BMP3_IIR_FILTER_COEFF_15 (0x04) |
#define | BMP3_IIR_FILTER_COEFF_31 (0x05) |
#define | BMP3_IIR_FILTER_COEFF_63 (0x06) |
#define | BMP3_IIR_FILTER_COEFF_127 (0x07) |
#define | BMP3_ODR_200_HZ (0x00) |
#define | BMP3_ODR_100_HZ (0x01) |
#define | BMP3_ODR_50_HZ (0x02) |
#define | BMP3_ODR_25_HZ (0x03) |
#define | BMP3_CHIP_ID_ADDR (0x00) |
#define | BMP3_ERR_REG_ADDR (0x02) |
#define | BMP3_SENS_STATUS_REG_ADDR (0x03) |
#define | BMP3_DATA_ADDR (0x04) |
#define | BMP3_PWR_CTRL_ADDR (0x1B) |
#define | BMP3_OSR_ADDR (0X1C) |
#define | BMP3_CALIB_DATA_ADDR (0x31) |
#define | BMP3_CMD_ADDR (0x7E) |
#define | BMP3_FATAL_ERR (0x01) |
#define | BMP3_CMD_ERR (0x02) |
#define | BMP3_CONF_ERR (0x04) |
#define | BMP3_CMD_RDY (0x10) |
#define | BMP3_DRDY_PRESS (0x20) |
#define | BMP3_DRDY_TEMP (0x40) |
#define | BMP3_SLEEP_MODE (0x00) |
#define | BMP3_FORCED_MODE (0x01) |
#define | BMP3_NORMAL_MODE (0x03) |
#define | BMP3_ENABLE (0x01) |
#define | BMP3_DISABLE (0x00) |
#define | BMP3_PRESS (1) |
#define | BMP3_TEMP (1 << 1) |
#define | BMP3_ALL (0x03) |
#define | BMP3_CALIB_DATA_LEN (21) |
#define | BMP3_P_T_DATA_LEN (6) |
#define | BMP3_PRESS_EN_SEL (1 << 1) |
#define | BMP3_TEMP_EN_SEL (1 << 2) |
#define | BMP3_PRESS_OS_SEL (1 << 4) |
#define | BMP3_OP_MODE_MSK (0x30) |
#define | BMP3_OP_MODE_POS (0x04) |
#define | BMP3_PRESS_EN_MSK (0x01) |
#define | BMP3_TEMP_EN_MSK (0x02) |
#define | BMP3_TEMP_EN_POS (0x01) |
#define | BMP3_IIR_FILTER_MSK (0x0E) |
#define | BMP3_IIR_FILTER_POS (0x01) |
#define | BMP3_ODR_MSK (0x1F) |
#define | BMP3_PRESS_OS_MSK (0x07) |
#define | BMP3_TEMP_OS_MSK (0x38) |
#define | BMP3_TEMP_OS_POS (0x03) |
#define | BMP3_SET_BITS(reg_data, bitname, data) |
#define | BMP3_SET_BITS_POS_0(reg_data, bitname, data) |
#define | BMP3_GET_BITS(reg_data, bitname) |
#define | BMP3_GET_BITS_POS_0(reg_data, bitname) (reg_data & (bitname##_MSK)) |
#define | BMP3_POST_SLEEP_WAIT_TIME 5000 |
#define | BMP3_POST_RESET_WAIT_TIME 2000 |
#define | BMP3_POST_INIT_WAIT_TIME 40000 |
#define | BMP3_TRIM_CRC_DATA_ADDR 0x30 |
#define | BPM3_CMD_SOFT_RESET 0xB6 |
#define | BMP3_ODR_ADDR 0x1D |
#define | BMP3_IIR_ADDR 0x1F |
#define | POWER_CNTL (0x0006) |
#define | ODR_FILTER (0x00F0) |
#define | INT_CTRL (0x0708) |
#define | ADV_SETT (0x1800) |
Typedefs | |
typedef IBMP388 *(* | BMP388_constructor) (uint8_t, uint32_t) |
Functions | |
IBMP388 * | bmp388_spi_interface (uint8_t busnum, uint32_t device) |
IBMP388 * | bmp388_i2c_interface (uint8_t busnum, uint32_t device) |
#define BMP3_CALIB_DATA_ADDR (0x31) |
Definition at line 86 of file bmp388.h.
Referenced by BMP388::init().
#define BMP3_CALIB_DATA_LEN (21) |
Definition at line 115 of file bmp388.h.
Referenced by BMP388::validate_trimming_param().
#define BMP3_CHIP_ID (0x50) |
Definition at line 53 of file bmp388.h.
Referenced by BMP388::init().
#define BMP3_CHIP_ID_ADDR (0x00) |
Definition at line 80 of file bmp388.h.
Referenced by BMP388::init().
#define BMP3_CMD_ADDR (0x7E) |
Definition at line 87 of file bmp388.h.
Referenced by BMP388::soft_reset().
#define BMP3_CMD_ERR (0x02) |
Definition at line 91 of file bmp388.h.
Referenced by BMP388::soft_reset().
#define BMP3_CMD_RDY (0x10) |
Definition at line 95 of file bmp388.h.
Referenced by BMP388::soft_reset().
#define BMP3_DATA_ADDR (0x04) |
Definition at line 83 of file bmp388.h.
Referenced by BMP388::get_sensor_data().
#define BMP3_ENABLE (0x01) |
Definition at line 104 of file bmp388.h.
Referenced by BMP388::set_sensor_settings().
#define BMP3_ERR_REG_ADDR (0x02) |
Definition at line 81 of file bmp388.h.
Referenced by BMP388::soft_reset().
#define BMP3_FORCED_MODE (0x01) |
Definition at line 101 of file bmp388.h.
Referenced by BMP388::measure().
#define BMP3_GET_BITS | ( | reg_data, | |
bitname | |||
) |
Definition at line 153 of file bmp388.h.
Referenced by BMP388::set_op_mode().
#define BMP3_GET_BITS_POS_0 | ( | reg_data, | |
bitname | |||
) | (reg_data & (bitname##_MSK)) |
#define BMP3_IIR_ADDR 0x1F |
Definition at line 166 of file bmp388.h.
Referenced by BMP388::set_sensor_settings().
#define BMP3_NO_OVERSAMPLING (0x00) |
Definition at line 56 of file bmp388.h.
Referenced by BMP388::get_measurement_time().
#define BMP3_ODR_ADDR 0x1D |
Definition at line 165 of file bmp388.h.
Referenced by BMP388::set_sensor_settings().
#define BMP3_OP_MODE_MSK (0x30) |
Definition at line 126 of file bmp388.h.
Referenced by BMP388::set_op_mode().
#define BMP3_OSR_ADDR (0X1C) |
Definition at line 85 of file bmp388.h.
Referenced by BMP388::set_sensor_settings().
#define BMP3_OVERSAMPLING_16X (0x04) |
Definition at line 60 of file bmp388.h.
Referenced by BMP388::get_measurement_time().
#define BMP3_OVERSAMPLING_2X (0x01) |
Definition at line 57 of file bmp388.h.
Referenced by BMP388::get_measurement_time().
#define BMP3_OVERSAMPLING_32X (0x05) |
Definition at line 61 of file bmp388.h.
Referenced by BMP388::get_measurement_time().
#define BMP3_OVERSAMPLING_4X (0x02) |
Definition at line 58 of file bmp388.h.
Referenced by BMP388::get_measurement_time().
#define BMP3_OVERSAMPLING_8X (0x03) |
Definition at line 59 of file bmp388.h.
Referenced by BMP388::get_measurement_time().
#define BMP3_P_T_DATA_LEN (6) |
Definition at line 116 of file bmp388.h.
Referenced by BMP388::get_sensor_data().
#define BMP3_POST_RESET_WAIT_TIME 2000 |
Definition at line 161 of file bmp388.h.
Referenced by BMP388::soft_reset().
#define BMP3_POST_SLEEP_WAIT_TIME 5000 |
Definition at line 160 of file bmp388.h.
Referenced by BMP388::set_op_mode().
#define BMP3_PRESS (1) |
Definition at line 110 of file bmp388.h.
Referenced by BMP388::collect(), and BMP388::compensate_data().
#define BMP3_PWR_CTRL_ADDR (0x1B) |
Definition at line 84 of file bmp388.h.
Referenced by BMP388::set_op_mode(), and BMP388::set_sensor_settings().
#define BMP3_SENS_STATUS_REG_ADDR (0x03) |
Definition at line 82 of file bmp388.h.
Referenced by BMP388::soft_reset().
#define BMP3_SET_BITS | ( | reg_data, | |
bitname, | |||
data | |||
) |
Definition at line 144 of file bmp388.h.
Referenced by BMP388::set_op_mode(), and BMP388::set_sensor_settings().
#define BMP3_SET_BITS_POS_0 | ( | reg_data, | |
bitname, | |||
data | |||
) |
Definition at line 149 of file bmp388.h.
Referenced by BMP388::set_sensor_settings().
#define BMP3_SLEEP_MODE (0x00) |
Definition at line 100 of file bmp388.h.
Referenced by BMP388::set_op_mode().
#define BMP3_TEMP (1 << 1) |
Definition at line 111 of file bmp388.h.
Referenced by BMP388::collect(), and BMP388::compensate_data().
#define BMP3_TRIM_CRC_DATA_ADDR 0x30 |
Definition at line 163 of file bmp388.h.
Referenced by BMP388::validate_trimming_param().
#define BPM3_CMD_SOFT_RESET 0xB6 |
Definition at line 164 of file bmp388.h.
Referenced by BMP388::soft_reset().
IBMP388* bmp388_i2c_interface | ( | uint8_t | busnum, |
uint32_t | device | ||
) |
IBMP388* bmp388_spi_interface | ( | uint8_t | busnum, |
uint32_t | device | ||
) |