diff --git a/boards/px4/fmu-v5x/default.cmake b/boards/px4/fmu-v5x/default.cmake index 054b543564b6..6f75f626597e 100644 --- a/boards/px4/fmu-v5x/default.cmake +++ b/boards/px4/fmu-v5x/default.cmake @@ -19,7 +19,9 @@ px4_add_board( GPS2:/dev/ttyS0 DRIVERS - barometer # all available barometer drivers + #barometer # all available barometer drivers + barometer/bmp388 + barometer/ms5611 batt_smbus camera_capture camera_trigger diff --git a/boards/px4/fmu-v5x/init/rc.board_sensors b/boards/px4/fmu-v5x/init/rc.board_sensors index c86192a53732..847b68633e52 100644 --- a/boards/px4/fmu-v5x/init/rc.board_sensors +++ b/boards/px4/fmu-v5x/init/rc.board_sensors @@ -30,7 +30,7 @@ bmm150 start # Possible internal Barro bmp388 -I start -#bmp388 -J start fixme +bmp388 -J start # Possible pmw3901 optical flow sensor pmw3901 start diff --git a/boards/px4/fmu-v5x/src/board_config.h b/boards/px4/fmu-v5x/src/board_config.h index 030bca52c014..4de9940cf961 100644 --- a/boards/px4/fmu-v5x/src/board_config.h +++ b/boards/px4/fmu-v5x/src/board_config.h @@ -279,6 +279,9 @@ #define BOARD_NUMBER_I2C_BUSES 4 #define BOARD_I2C_BUS_CLOCK_INIT {100000, 100000, 100000, 100000} +#define PX4_I2C_OBDEV_BMP388 0x76 // On IMU +#define PX4_I2C_OBDEV1_BMP388 0x77 // On FMUM + #define GPIO_I2C4_DRDY1_BMP388 /* PG5 */ (GPIO_INPUT|GPIO_FLOAT|GPIO_EXTI|GPIO_PORTG|GPIO_PIN5) #define A71CH_nRST /* PG6 */ (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_2MHz|GPIO_OUTPUT_CLEAR|GPIO_PORTG|GPIO_PIN6) diff --git a/src/drivers/barometer/CMakeLists.txt b/src/drivers/barometer/CMakeLists.txt index 8e61b98696f5..1619bce11797 100644 --- a/src/drivers/barometer/CMakeLists.txt +++ b/src/drivers/barometer/CMakeLists.txt @@ -32,6 +32,7 @@ ############################################################################ add_subdirectory(bmp280) +add_subdirectory(bmp388) add_subdirectory(lps22hb) #add_subdirectory(lps25h) # not ready for general inclusion #add_subdirectory(mpl3115a2) # not ready for general inclusion diff --git a/src/drivers/barometer/bmp388/CMakeLists.txt b/src/drivers/barometer/bmp388/CMakeLists.txt new file mode 100644 index 000000000000..cf22eef6f4b0 --- /dev/null +++ b/src/drivers/barometer/bmp388/CMakeLists.txt @@ -0,0 +1,48 @@ +############################################################################ +# +# Copyright (c) 2019 PX4 Development Team. All rights reserved. +# +# Redistribution and use in source and binary forms, with or without +# modification, are permitted provided that the following conditions +# are met: +# +# 1. Redistributions of source code must retain the above copyright +# notice, this list of conditions and the following disclaimer. +# 2. Redistributions in binary form must reproduce the above copyright +# notice, this list of conditions and the following disclaimer in +# the documentation and/or other materials provided with the +# distribution. +# 3. Neither the name PX4 nor the names of its contributors may be +# used to endorse or promote products derived from this software +# without specific prior written permission. +# +# THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS +# "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT +# LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS +# FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE +# COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, +# INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, +# BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS +# OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED +# AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT +# LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN +# ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE +# POSSIBILITY OF SUCH DAMAGE. +# +############################################################################ + +px4_add_module( + MODULE drivers__barometer__bmp388 + MAIN bmp388 + COMPILE_FLAGS + -Wno-cast-align # TODO: fix and enable + STACK_MAIN + 1200 + SRCS + bmp388_spi.cpp + bmp388_i2c.cpp + bmp388.cpp + DEPENDS + drivers_barometer + px4_work_queue + ) diff --git a/src/drivers/barometer/bmp388/bmp388.cpp b/src/drivers/barometer/bmp388/bmp388.cpp new file mode 100644 index 000000000000..ad00a9e6e621 --- /dev/null +++ b/src/drivers/barometer/bmp388/bmp388.cpp @@ -0,0 +1,899 @@ +/**************************************************************************** + * + * Copyright (c) 2019 PX4 Development Team. All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * 1. Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * 2. Redistributions in binary form must reproduce the above copyright + * notice, this list of conditions and the following disclaimer in + * the documentation and/or other materials provided with the + * distribution. + * 3. Neither the name PX4 nor the names of its contributors may be + * used to endorse or promote products derived from this software + * without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS + * OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED + * AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + * + ****************************************************************************/ + +/** + * @file bmp388.cpp + * Driver for the BMP388 barometric pressure sensor connected via I2C + * (SPI still TODO/test). + */ + +#include "bmp388.h" + +#include + +enum BMP388_BUS { + BMP388_BUS_ALL = 0, + BMP388_BUS_I2C_INTERNAL, + BMP388_BUS_I2C_INTERNAL1, + BMP388_BUS_I2C_EXTERNAL, + BMP388_BUS_SPI_INTERNAL, + BMP388_BUS_SPI_EXTERNAL +}; + +/* + * BMP388 internal constants and data structures. + */ + +class BMP388 : public cdev::CDev, public px4::ScheduledWorkItem +{ +public: + BMP388(bmp388::IBMP388 *interface, const char *path); + virtual ~BMP388(); + + virtual int init(); + + /** + * Diagnostics - print some basic information about the driver. + */ + void print_info(); + +private: + PX4Barometer _px4_baro; + + bmp388::IBMP388 *_interface; + + bool _running{false}; + + uint8_t _curr_ctrl{0}; + + unsigned _report_interval{0}; // 0 - no cycling, otherwise period of sending a report + unsigned _max_measure_interval{0}; // interval in microseconds needed to measure + + + bool _collect_phase{false}; + + perf_counter_t _sample_perf; + perf_counter_t _measure_perf; + perf_counter_t _comms_errors; + + struct bmp388::calibration_s *_cal; // stored calibration constants + struct bmp388::fcalibration_s _fcal; // pre processed calibration constants + + float _P; /* in Pa */ + float _T; /* in K */ + + + /* periodic execution helpers */ + void start_cycle(); + void stop_cycle(); + + void Run() override; + + int measure(); //start measure + int collect(); //get results and publish + + // from BMP3 library... + bool soft_reset(); + bool get_calib_data(); + bool validate_trimming_param(); + bool set_sensor_settings(); + bool set_op_mode(uint8_t op_mode); + + bool get_sensor_data(uint8_t sensor_comp, struct bmp3_data *comp_data); + bool compensate_data(uint8_t sensor_comp, const struct bmp3_uncomp_data *uncomp_data, struct bmp3_data *comp_data); +}; + +/* + * Driver 'main' command. + */ +extern "C" __EXPORT int bmp388_main(int argc, char *argv[]); + +BMP388::BMP388(bmp388::IBMP388 *interface, const char *path) : + CDev(path), + ScheduledWorkItem(px4::device_bus_to_wq(interface->get_device_id())), + _px4_baro(interface->get_device_id()), + _interface(interface), + _sample_perf(perf_alloc(PC_ELAPSED, "bmp388: read")), + _measure_perf(perf_alloc(PC_ELAPSED, "bmp388: measure")), + _comms_errors(perf_alloc(PC_COUNT, "bmp388: comms errors")) +{ + _px4_baro.set_device_type(DRV_DEVTYPE_BMP388); +} + +BMP388::~BMP388() +{ + // make sure we are truly inactive + stop_cycle(); + + // free perf counters + perf_free(_sample_perf); + perf_free(_measure_perf); + perf_free(_comms_errors); + + delete _interface; +} + +bool +BMP388::soft_reset() +{ + bool result = false; + uint8_t status; + int ret; + + status = _interface->get_reg(BMP3_SENS_STATUS_REG_ADDR); + + if (status & BMP3_CMD_RDY) { + ret = _interface->set_reg(BPM3_CMD_SOFT_RESET, BMP3_CMD_ADDR); + + if (ret == OK) { + usleep(BMP3_POST_RESET_WAIT_TIME); + status = _interface->get_reg(BMP3_ERR_REG_ADDR); + + if ((status & BMP3_CMD_ERR) == 0) { + result = true; + } + } + } + + return result; +} + +/* + * @brief function to calculate CRC for the trimming parameters + * + * See https://github.com/BoschSensortec/BMP3-Sensor-API/blob/master/self-test/bmp3_selftest.c + * */ +static int8_t cal_crc(uint8_t seed, uint8_t data) +{ + int8_t poly = 0x1D; + int8_t var2; + uint8_t i; + + for (i = 0; i < 8; i++) { + if ((seed & 0x80) ^ (data & 0x80)) { + var2 = 1; + + } else { + var2 = 0; + } + + seed = (seed & 0x7F) << 1; + data = (data & 0x7F) << 1; + seed = seed ^ (uint8_t)(poly * var2); + } + + return (int8_t)seed; +} + +/* + * @brief Function to verify the trimming parameters + * + * See https://github.com/BoschSensortec/BMP3-Sensor-API/blob/master/self-test/bmp3_selftest.c + * */ +bool +BMP388::validate_trimming_param() +{ + bool result = false; + uint8_t crc = 0xFF; + uint8_t stored_crc; + uint8_t trim_param[21]; + uint8_t i; + + memcpy(&trim_param, _cal, 21); + + for (i = 0; i < 21; i++) { + crc = (uint8_t)cal_crc(crc, trim_param[i]); + } + + crc = (crc ^ 0xFF); + + stored_crc = _interface->get_reg(BMP3_TRIM_CRC_DATA_ADDR); + + if (stored_crc == crc) { + result = true; + } + + return result; +} + +bool +BMP388::set_sensor_settings() +{ + int ret; + + uint8_t press_os = BMP3_NO_OVERSAMPLING; + uint8_t temp_os = BMP3_NO_OVERSAMPLING; + + /* + Pressure Temperature Measurement + Oversample Oversample Time Max + x1 1x 6.4 ms + x2 1x 8.7 ms + x4 1x 13.3 ms + x8 1x 22.5 ms + x16 2x 43.2 ms + */ + _max_measure_interval = 6400; + + /* Select the pressure and temperature sensor to be enabled */ + uint8_t pwc_ctl_reg = 0; + pwc_ctl_reg = BMP3_SET_BITS_POS_0(pwc_ctl_reg, BMP3_PRESS_EN, BMP3_ENABLE); + pwc_ctl_reg = BMP3_SET_BITS(pwc_ctl_reg, BMP3_TEMP_EN, BMP3_ENABLE); + + ret = _interface->set_reg(pwc_ctl_reg, BMP3_PWR_CTRL_ADDR); + + if (ret != OK) { + PX4_WARN("failed to set settings BMP3_PWR_CTRL_ADDR"); + return false; + } + + /* Select the output data rate and over sampling settings for pressure and temperature */ + uint8_t osr_ctl_reg = 0; + osr_ctl_reg = BMP3_SET_BITS_POS_0(osr_ctl_reg, BMP3_PRESS_OS, press_os); + osr_ctl_reg = BMP3_SET_BITS(osr_ctl_reg, BMP3_TEMP_OS, temp_os); + + /* 0x1C is the register address of over sampling register */ + ret = _interface->set_reg(osr_ctl_reg, BMP3_OSR_ADDR); + + if (ret != OK) { + PX4_WARN("failed to set settings BMP3_OSR_ADDR"); + return false; + } + + uint8_t odr_ctl_reg = 0; + odr_ctl_reg = BMP3_SET_BITS_POS_0(odr_ctl_reg, BMP3_ODR, BMP3_ODR_25_HZ); + + /* 0x1D is the register address of output data rate register */ + ret = _interface->set_reg(odr_ctl_reg, 0x1D); + + if (ret != OK) { + PX4_WARN("failed to set settingsoutput data rate register"); + return false; + } + + return true; +} + + +/*! + * @brief This API sets the power mode of the sensor. + */ +bool +BMP388::set_op_mode(uint8_t op_mode) +{ + bool result = false; + uint8_t last_set_mode; + uint8_t op_mode_reg_val; + int ret = OK; + + op_mode_reg_val = _interface->get_reg(BMP3_PWR_CTRL_ADDR); + last_set_mode = BMP3_GET_BITS(op_mode_reg_val, BMP3_OP_MODE); + + /* If the sensor is not in sleep mode put the device to sleep + * mode */ + if (last_set_mode != BMP3_SLEEP_MODE) { + /* Device should be put to sleep before transiting to + * forced mode or normal mode */ + op_mode_reg_val = op_mode_reg_val & (~(BMP3_OP_MODE_MSK)); + ret = _interface->set_reg(op_mode_reg_val, BMP3_PWR_CTRL_ADDR); + + if (ret != OK) { + return false; + } + + px4_usleep(BMP3_POST_SLEEP_WAIT_TIME); + } + + if (ret == OK) { + op_mode_reg_val = _interface->get_reg(BMP3_PWR_CTRL_ADDR); + op_mode_reg_val = BMP3_SET_BITS(op_mode_reg_val, BMP3_OP_MODE, op_mode); + ret = _interface->set_reg(op_mode_reg_val, BMP3_PWR_CTRL_ADDR); + + if (ret != OK) { + return false; + } + + result = true; + } + + return result; +} + +/*! + * @brief This internal API is used to parse the pressure or temperature or + * both the data and store it in the bmp3_uncomp_data structure instance. + */ +static void parse_sensor_data(const uint8_t *reg_data, struct bmp3_uncomp_data *uncomp_data) +{ + /* Temporary variables to store the sensor data */ + uint32_t data_xlsb; + uint32_t data_lsb; + uint32_t data_msb; + + /* Store the parsed register values for pressure data */ + data_xlsb = (uint32_t)reg_data[0]; + data_lsb = (uint32_t)reg_data[1] << 8; + data_msb = (uint32_t)reg_data[2] << 16; + uncomp_data->pressure = data_msb | data_lsb | data_xlsb; + + /* Store the parsed register values for temperature data */ + data_xlsb = (uint32_t)reg_data[3]; + data_lsb = (uint32_t)reg_data[4] << 8; + data_msb = (uint32_t)reg_data[5] << 16; + uncomp_data->temperature = data_msb | data_lsb | data_xlsb; +} + + +/*! + * @brief This internal API is used to compensate the raw temperature data and + * return the compensated temperature data in integer data type. + * For eg if returned temperature is 2426 then it is 2426/100 = 24.26 deg Celsius + */ +static int64_t compensate_temperature(const struct bmp3_uncomp_data *uncomp_data, struct bmp3_calib_data *calib_data) +{ + int64_t partial_data1; + int64_t partial_data2; + int64_t partial_data3; + int64_t partial_data4; + int64_t partial_data5; + int64_t partial_data6; + int64_t comp_temp; + + partial_data1 = ((int64_t)uncomp_data->temperature - (256 * calib_data->reg_calib_data.par_t1)); + partial_data2 = calib_data->reg_calib_data.par_t2 * partial_data1; + partial_data3 = (partial_data1 * partial_data1); + partial_data4 = (int64_t)partial_data3 * calib_data->reg_calib_data.par_t3; + partial_data5 = ((int64_t)(partial_data2 * 262144) + partial_data4); + partial_data6 = partial_data5 / 4294967296; + + /* Store t_lin in dev. structure for pressure calculation */ + calib_data->reg_calib_data.t_lin = partial_data6; + comp_temp = (int64_t)((partial_data6 * 25) / 16384); + + return comp_temp; +} + +/*! + * @brief This internal API is used to compensate the raw pressure data and + * return the compensated pressure data in integer data type. + * for eg return if pressure is 9528709 which is 9528709/100 = 95287.09 Pascal or 952.8709 hecto Pascal + */ +static uint64_t compensate_pressure(const struct bmp3_uncomp_data *uncomp_data, + const struct bmp3_calib_data *calib_data) +{ + const struct bmp3_reg_calib_data *reg_calib_data = &calib_data->reg_calib_data; + int64_t partial_data1; + int64_t partial_data2; + int64_t partial_data3; + int64_t partial_data4; + int64_t partial_data5; + int64_t partial_data6; + int64_t offset; + int64_t sensitivity; + uint64_t comp_press; + + partial_data1 = reg_calib_data->t_lin * reg_calib_data->t_lin; + partial_data2 = partial_data1 / 64; + partial_data3 = (partial_data2 * reg_calib_data->t_lin) / 256; + partial_data4 = (reg_calib_data->par_p8 * partial_data3) / 32; + partial_data5 = (reg_calib_data->par_p7 * partial_data1) * 16; + partial_data6 = (reg_calib_data->par_p6 * reg_calib_data->t_lin) * 4194304; + offset = (reg_calib_data->par_p5 * 140737488355328) + partial_data4 + partial_data5 + partial_data6; + partial_data2 = (reg_calib_data->par_p4 * partial_data3) / 32; + partial_data4 = (reg_calib_data->par_p3 * partial_data1) * 4; + partial_data5 = (reg_calib_data->par_p2 - 16384) * reg_calib_data->t_lin * 2097152; + sensitivity = ((reg_calib_data->par_p1 - 16384) * 70368744177664) + partial_data2 + partial_data4 + partial_data5; + partial_data1 = (sensitivity / 16777216) * uncomp_data->pressure; + partial_data2 = reg_calib_data->par_p10 * reg_calib_data->t_lin; + partial_data3 = partial_data2 + (65536 * reg_calib_data->par_p9); + partial_data4 = (partial_data3 * uncomp_data->pressure) / 8192; + /*dividing by 10 followed by multiplying by 10 to avoid overflow caused by (uncomp_data->pressure * partial_data4) */ + partial_data5 = (uncomp_data->pressure * (partial_data4 / 10)) / 512; + partial_data5 = partial_data5 * 10; + partial_data6 = (int64_t)((uint64_t)uncomp_data->pressure * (uint64_t)uncomp_data->pressure); + partial_data2 = (reg_calib_data->par_p11 * partial_data6) / 65536; + partial_data3 = (partial_data2 * uncomp_data->pressure) / 128; + partial_data4 = (offset / 4) + partial_data1 + partial_data5 + partial_data3; + comp_press = (((uint64_t)partial_data4 * 25) / (uint64_t)1099511627776); + + return comp_press; +} + +/*! + * @brief This internal API is used to compensate the pressure or temperature + * or both the data according to the component selected by the user. + */ +bool +BMP388::compensate_data(uint8_t sensor_comp, + const struct bmp3_uncomp_data *uncomp_data, + struct bmp3_data *comp_data) +{ + int8_t rslt = OK; + struct bmp3_calib_data calib_data = {0}; + struct bmp3_reg_calib_data *reg_calib_data = &calib_data.reg_calib_data; + memcpy(reg_calib_data, _cal, 21); + + if ((uncomp_data != NULL) && (comp_data != NULL)) { + if (sensor_comp & (BMP3_PRESS | BMP3_TEMP)) { + comp_data->temperature = compensate_temperature(uncomp_data, &calib_data); + } + + if (sensor_comp & BMP3_PRESS) { + /* Compensate the pressure data */ + comp_data->pressure = compensate_pressure(uncomp_data, &calib_data); + } + + } else { + rslt = -1; + } + + return (rslt == 0); +} + +/*! + * @brief This API reads the pressure, temperature or both data from the + * sensor, compensates the data and store it in the bmp3_data structure + * instance passed by the user. + */ +bool +BMP388::get_sensor_data(uint8_t sensor_comp, struct bmp3_data *comp_data) +{ + bool result = false; + int8_t rslt; + + /* Array to store the pressure and temperature data read from + * the sensor */ + uint8_t reg_data[BMP3_P_T_DATA_LEN] = { 0 }; + struct bmp3_uncomp_data uncomp_data = { 0 }; + + /* Read the pressure and temperature data from the sensor */ + rslt = _interface->get_reg_buf(BMP3_DATA_ADDR, reg_data, BMP3_P_T_DATA_LEN); + + if (rslt == OK) { + /* Parse the read data from the sensor */ + parse_sensor_data(reg_data, &uncomp_data); + + /* Compensate the pressure/temperature/both data read + * from the sensor */ + result = compensate_data(sensor_comp, &uncomp_data, comp_data); + } + + return result; +} + +int +BMP388::init() +{ + int ret = CDev::init(); + + if (ret != OK) { + PX4_ERR("CDev init failed"); + return ret; + } + + if (!soft_reset()) { + PX4_WARN("failed to reset baro during init"); + return -EIO; + } + + if (_interface->get_reg(BMP3_CHIP_ID_ADDR) != BMP3_CHIP_ID) { + PX4_WARN("id of your baro is not: 0x%02x", BMP3_CHIP_ID); + return -EIO; + } + + _cal = _interface->get_calibration(BMP3_CALIB_DATA_ADDR); + + if (!_cal) { + PX4_WARN("failed to get baro cal init"); + return -EIO; + } + + if (!validate_trimming_param()) { + PX4_WARN("failed to validate trim param"); + return -EIO; + } + + if (!set_sensor_settings()) { + PX4_WARN("failed to set sensor settings"); + return -EIO; + } + + /* do a first measurement cycle to populate reports with valid data */ + if (measure()) { + return -EIO; + } + + usleep(_max_measure_interval); + + if (collect()) { + return -EIO; + } + + return OK; +} + +void +BMP388::start_cycle() +{ + /* reset the report ring and state machine */ + _collect_phase = false; + _running = true; + + /* schedule a cycle to start things */ + ScheduleNow(); +} + +void +BMP388::stop_cycle() +{ + _running = false; + + ScheduleClear(); +} + +void +BMP388::Run() +{ + if (_collect_phase) { + collect(); + unsigned wait_gap = _report_interval - _max_measure_interval; + + if ((wait_gap != 0) && (_running)) { + //need to wait some time before new measurement + ScheduleDelayed(wait_gap); + + return; + } + + } + + measure(); + + if (_running) { + ScheduleDelayed(_max_measure_interval); + } +} + +int +BMP388::measure() +{ + _collect_phase = true; + + perf_begin(_measure_perf); + + /* start measure */ + if (!set_op_mode(BMP3_FORCED_MODE)) { + PX4_WARN("failed to set operating mode"); + perf_count(_comms_errors); + perf_cancel(_measure_perf); + return -EIO; + } + + perf_end(_measure_perf); + + return OK; +} + +int +BMP388::collect() +{ + uint8_t sensor_comp = BMP3_PRESS | BMP3_TEMP; + + _collect_phase = false; + + perf_begin(_sample_perf); + + /* this should be fairly close to the end of the conversion, so the best approximation of the time */ + const hrt_abstime timestamp_sample = hrt_absolute_time(); + + /* Variable used to store the compensated data */ + bmp3_data data{}; + + if (!get_sensor_data(sensor_comp, &data)) { + perf_count(_comms_errors); + perf_cancel(_sample_perf); + return -EIO; + } + + _px4_baro.set_error_count(perf_event_count(_comms_errors)); + + // Temperature + _T = (float)(data.temperature / 100.0f); + + // Pressure + _P = (float)(data.pressure / 100.0f); // to hecto Pascal + + float temperature = _T; + float pressure = _P / 100.0f; // to mbar + + _px4_baro.set_temperature(temperature); + _px4_baro.update(timestamp_sample, pressure); // to mbar + + perf_end(_sample_perf); + + return OK; +} + +void +BMP388::print_info() +{ + perf_print_counter(_sample_perf); + perf_print_counter(_comms_errors); + printf("poll interval: %u us \n", _report_interval); + + _px4_baro.print_status(); +} + +/** + * Local functions in support of the shell command. + */ +namespace bmp388 +{ + +/* + list of supported bus configurations + */ +struct bmp388_bus_option { + enum BMP388_BUS busid; + const char *devpath; + BMP388_constructor interface_constructor; + uint8_t busnum; + uint32_t device; + bool external; + BMP388 *dev; +} bus_options[] = { +#if defined(PX4_SPIDEV_EXT_BARO) && defined(PX4_SPI_BUS_EXT) + { BMP388_BUS_SPI_EXTERNAL, "/dev/bmp388_spi_ext", &bmp388_spi_interface, PX4_SPI_BUS_EXT, PX4_SPIDEV_EXT_BARO, true, NULL }, +#endif +#if defined(PX4_SPIDEV_BARO) +# if defined(PX4_SPIDEV_BARO_BUS) + { BMP388_BUS_SPI_INTERNAL, "/dev/bmp388_spi_int", &bmp388_spi_interface, PX4_SPIDEV_BARO_BUS, PX4_SPIDEV_BARO, false, NULL }, +# else + { BMP388_BUS_SPI_INTERNAL, "/dev/bmp388_spi_int", &bmp388_spi_interface, PX4_SPI_BUS_SENSORS, PX4_SPIDEV_BARO, false, NULL }, +# endif +#endif +#if defined(PX4_I2C_BUS_ONBOARD) && defined(PX4_I2C_OBDEV_BMP388) + { BMP388_BUS_I2C_INTERNAL, "/dev/bmp388_i2c_int", &bmp388_i2c_interface, PX4_I2C_BUS_ONBOARD, PX4_I2C_OBDEV_BMP388, false, NULL }, +#endif +#if defined(PX4_I2C_BUS_ONBOARD) && defined(PX4_I2C_OBDEV1_BMP388) + { BMP388_BUS_I2C_INTERNAL1, "/dev/bmp388_i2c_int1", &bmp388_i2c_interface, PX4_I2C_BUS_ONBOARD, PX4_I2C_OBDEV1_BMP388, false, NULL }, +#endif +#if defined(PX4_I2C_BUS_EXPANSION) && defined(PX4_I2C_OBDEV_BMP388) + { BMP388_BUS_I2C_EXTERNAL, "/dev/bmp388_i2c_ext", &bmp388_i2c_interface, PX4_I2C_BUS_EXPANSION, PX4_I2C_OBDEV_BMP388, true, NULL }, +#endif +}; +#define NUM_BUS_OPTIONS (sizeof(bus_options)/sizeof(bus_options[0])) + +bool start_bus(struct bmp388_bus_option &bus); +struct bmp388_bus_option &find_bus(enum BMP388_BUS busid); +void start(enum BMP388_BUS busid); +void test(enum BMP388_BUS busid); +void reset(enum BMP388_BUS busid); +void info(); +void usage(); + + +/** + * Start the driver. + */ +bool +start_bus(struct bmp388_bus_option &bus) +{ + if (bus.dev != nullptr) { + PX4_ERR("bus option already started"); + exit(1); + } + + bmp388::IBMP388 *interface = bus.interface_constructor(bus.busnum, bus.device, bus.external); + + if (interface->init() != OK) { + delete interface; + PX4_WARN("no device on bus %u", (unsigned)bus.busid); + return false; + } + + bus.dev = new BMP388(interface, bus.devpath); + + if (bus.dev == nullptr) { + return false; + } + + if (OK != bus.dev->init()) { + delete bus.dev; + bus.dev = nullptr; + return false; + } + + int fd = open(bus.devpath, O_RDONLY); + + /* set the poll rate to default, starts automatic data collection */ + if (fd == -1) { + PX4_ERR("can't open baro device"); + exit(1); + } + + if (ioctl(fd, SENSORIOCSPOLLRATE, SENSOR_POLLRATE_DEFAULT) < 0) { + close(fd); + PX4_ERR("failed setting default poll rate"); + exit(1); + } + + close(fd); + return true; +} + + +/** + * Start the driver. + * + * This function call only returns once the driver + * is either successfully up and running or failed to start. + */ +void +start(enum BMP388_BUS busid) +{ + uint8_t i; + bool started = false; + + for (i = 0; i < NUM_BUS_OPTIONS; i++) { + if (busid == BMP388_BUS_ALL && bus_options[i].dev != NULL) { + // this device is already started + continue; + } + + if (busid != BMP388_BUS_ALL && bus_options[i].busid != busid) { + // not the one that is asked for + continue; + } + + started |= start_bus(bus_options[i]); + } + + if (!started) { + PX4_WARN("bus option number is %d", i); + PX4_ERR("driver start failed"); + exit(1); + } + + // one or more drivers started OK + exit(0); +} + + +/** + * find a bus structure for a busid + */ +struct bmp388_bus_option &find_bus(enum BMP388_BUS busid) +{ + for (uint8_t i = 0; i < NUM_BUS_OPTIONS; i++) { + if ((busid == BMP388_BUS_ALL || + busid == bus_options[i].busid) && bus_options[i].dev != NULL) { + return bus_options[i]; + } + } + + PX4_ERR("bus %u not started", (unsigned)busid); + exit(1); +} + +/** + * Print a little info about the driver. + */ +void +info() +{ + for (uint8_t i = 0; i < NUM_BUS_OPTIONS; i++) { + struct bmp388_bus_option &bus = bus_options[i]; + + if (bus.dev != nullptr) { + PX4_WARN("%s", bus.devpath); + bus.dev->print_info(); + } + } + + exit(0); +} + +void +usage() +{ + PX4_WARN("missing command: try 'start', 'info'"); + PX4_WARN("options:"); + PX4_WARN(" -X (external I2C bus TODO)"); + PX4_WARN(" -I (internal I2C bus TODO)"); + PX4_WARN(" -S (external SPI bus)"); + PX4_WARN(" -s (internal SPI bus)"); +} + +} // namespace + +int +bmp388_main(int argc, char *argv[]) +{ + int myoptind = 1; + int ch; + const char *myoptarg = nullptr; + enum BMP388_BUS busid = BMP388_BUS_ALL; + + while ((ch = px4_getopt(argc, argv, "XIJSs", &myoptind, &myoptarg)) != EOF) { + switch (ch) { + case 'X': + busid = BMP388_BUS_I2C_EXTERNAL; + break; + + case 'I': + busid = BMP388_BUS_I2C_INTERNAL; + break; + + case 'J': + busid = BMP388_BUS_I2C_INTERNAL1; + break; + + case 'S': + busid = BMP388_BUS_SPI_EXTERNAL; + break; + + case 's': + busid = BMP388_BUS_SPI_INTERNAL; + break; + + default: + bmp388::usage(); + return 0; + } + } + + if (myoptind >= argc) { + bmp388::usage(); + return -1; + } + + const char *verb = argv[myoptind]; + + /* + * Start/load the driver. + */ + if (!strcmp(verb, "start")) { + bmp388::start(busid); + } + + /* + * Print driver information. + */ + if (!strcmp(verb, "info")) { + bmp388::info(); + } + + PX4_ERR("unrecognized command, try 'start', 'test', 'reset' or 'info'"); + return -1; +} diff --git a/src/drivers/barometer/bmp388/bmp388.h b/src/drivers/barometer/bmp388/bmp388.h new file mode 100644 index 000000000000..a2a7a71735c5 --- /dev/null +++ b/src/drivers/barometer/bmp388/bmp388.h @@ -0,0 +1,158 @@ +/**************************************************************************** + * + * Copyright (C) 2019 PX4 Development Team. All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * 1. Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * 2. Redistributions in binary form must reproduce the above copyright + * notice, this list of conditions and the following disclaimer in + * the documentation and/or other materials provided with the + * distribution. + * 3. Neither the name PX4 nor the names of its contributors may be + * used to endorse or promote products derived from this software + * without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS + * OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED + * AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + * + ****************************************************************************/ + +/** + * @file bmp388.h + * + * Shared defines for the bmp388 driver. + */ +#pragma once + +#include +#include + +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include + +#include "board_config.h" +#include "bmp3_defs.h" + +// From https://github.com/BoschSensortec/BMP3-Sensor-API/blob/master/self-test/bmp3_selftest.c +#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 + +// https://github.com/BoschSensortec/BMP3-Sensor-API/blob/master/bmp3.c +/*! Power control settings */ +#define POWER_CNTL (0x0006) +/*! Odr and filter settings */ +#define ODR_FILTER (0x00F0) +/*! Interrupt control settings */ +#define INT_CTRL (0x0708) +/*! Advance settings */ +#define ADV_SETT (0x1800) + +namespace bmp388 +{ + +#pragma pack(push,1) +struct calibration_s { + uint16_t par_t1; + uint16_t par_t2; + int8_t par_t3; + + int16_t par_p1; + int16_t par_p2; + int8_t par_p3; + int8_t par_p4; + uint16_t par_p5; + uint16_t par_p6; + int8_t par_p7; + int8_t par_p8; + int16_t par_p9; + int8_t par_p10; + int8_t par_p11; + +}; //calibration data + +struct data_s { + uint8_t p_msb; + uint8_t p_lsb; + uint8_t p_xlsb; + + uint8_t t_msb; + uint8_t t_lsb; + uint8_t t_xlsb; +}; // data +#pragma pack(pop) + +struct fcalibration_s { + float t1; + float t2; + float t3; + + float p1; + float p2; + float p3; + float p4; + float p5; + float p6; + float p7; + float p8; + float p9; +}; + +class IBMP388 +{ +public: + virtual ~IBMP388() = default; + + virtual bool is_external() = 0; + virtual int init() = 0; + + // read reg value + virtual uint8_t get_reg(uint8_t addr) = 0; + + // bulk read reg value + virtual int get_reg_buf(uint8_t addr, uint8_t *buf, uint8_t len) = 0; + + // write reg value + virtual int set_reg(uint8_t value, uint8_t addr) = 0; + + // bulk read of data into buffer, return same pointer + virtual bmp388::data_s *get_data(uint8_t addr) = 0; + + // bulk read of calibration data into buffer, return same pointer + virtual bmp388::calibration_s *get_calibration(uint8_t addr) = 0; + + virtual uint32_t get_device_id() const = 0; + +}; + +} /* namespace */ + + +/* interface factories */ +extern bmp388::IBMP388 *bmp388_spi_interface(uint8_t busnum, uint32_t device, bool external); +extern bmp388::IBMP388 *bmp388_i2c_interface(uint8_t busnum, uint32_t device, bool external); +typedef bmp388::IBMP388 *(*BMP388_constructor)(uint8_t, uint32_t, bool); diff --git a/src/drivers/barometer/bmp388/bmp388_i2c.cpp b/src/drivers/barometer/bmp388/bmp388_i2c.cpp new file mode 100644 index 000000000000..48c1cb7170c3 --- /dev/null +++ b/src/drivers/barometer/bmp388/bmp388_i2c.cpp @@ -0,0 +1,132 @@ +/**************************************************************************** + * + * Copyright (c) 2019 PX4 Development Team. All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * 1. Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * 2. Redistributions in binary form must reproduce the above copyright + * notice, this list of conditions and the following disclaimer in + * the documentation and/or other materials provided with the + * distribution. + * 3. Neither the name PX4 nor the names of its contributors may be + * used to endorse or promote products derived from this software + * without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS + * OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED + * AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + * + ****************************************************************************/ + +/** + * @file bmp388_spi.cpp + * + * SPI interface for BMP388 + */ + +#include "bmp388.h" + +#if defined(PX4_I2C_OBDEV_BMP388) || defined(PX4_I2C_EXT_OBDEV_BMP388) + +class BMP388_I2C: public device::I2C, public bmp388::IBMP388 +{ +public: + BMP388_I2C(uint8_t bus, uint32_t device, bool external); + virtual ~BMP388_I2C() = default; + + bool is_external(); + int init(); + + uint8_t get_reg(uint8_t addr); + int get_reg_buf(uint8_t addr, uint8_t *buf, uint8_t len); + int set_reg(uint8_t value, uint8_t addr); + bmp388::data_s *get_data(uint8_t addr); + bmp388::calibration_s *get_calibration(uint8_t addr); + + uint32_t get_device_id() const override { return device::I2C::get_device_id(); } + +private: + struct bmp388::calibration_s _cal; + struct bmp388::data_s _data; + bool _external; +}; + +bmp388::IBMP388 *bmp388_i2c_interface(uint8_t busnum, uint32_t device, bool external) +{ + return new BMP388_I2C(busnum, device, external); +} + +BMP388_I2C::BMP388_I2C(uint8_t bus, uint32_t device, bool external) : + I2C("BMP388_I2C", nullptr, bus, device, 100 * 1000) +{ + _external = external; +} + +bool BMP388_I2C::is_external() +{ + return _external; +} + +int BMP388_I2C::init() +{ + return I2C::init(); +} + +uint8_t BMP388_I2C::get_reg(uint8_t addr) +{ + uint8_t cmd[2] = { (uint8_t)(addr), 0}; + transfer(&cmd[0], 1, &cmd[1], 1); + + return cmd[1]; +} + +int BMP388_I2C::get_reg_buf(uint8_t addr, uint8_t *buf, uint8_t len) +{ + const uint8_t cmd = (uint8_t)(addr); + return transfer(&cmd, sizeof(cmd), buf, len); +} + +int BMP388_I2C::set_reg(uint8_t value, uint8_t addr) +{ + uint8_t cmd[2] = { (uint8_t)(addr), value}; + return transfer(cmd, sizeof(cmd), nullptr, 0); +} + +bmp388::data_s *BMP388_I2C::get_data(uint8_t addr) +{ + const uint8_t cmd = (uint8_t)(addr); + + if (transfer(&cmd, sizeof(cmd), (uint8_t *)&_data, sizeof(struct bmp388::data_s)) == OK) { + return (&_data); + + } else { + return nullptr; + } +} + +bmp388::calibration_s *BMP388_I2C::get_calibration(uint8_t addr) +{ + const uint8_t cmd = (uint8_t)(addr); + + if (transfer(&cmd, sizeof(cmd), (uint8_t *)&_cal, sizeof(struct bmp388::calibration_s)) == OK) { + return &(_cal); + + } else { + return nullptr; + } +} + +#endif /* PX4_I2C_OBDEV_BMP388 || PX4_I2C_EXT_OBDEV_BMP388 */ diff --git a/src/drivers/barometer/bmp388/bmp388_spi.cpp b/src/drivers/barometer/bmp388/bmp388_spi.cpp new file mode 100644 index 000000000000..dd6e4848f423 --- /dev/null +++ b/src/drivers/barometer/bmp388/bmp388_spi.cpp @@ -0,0 +1,142 @@ +/**************************************************************************** + * + * Copyright (c) 2019 PX4 Development Team. All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * 1. Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * 2. Redistributions in binary form must reproduce the above copyright + * notice, this list of conditions and the following disclaimer in + * the documentation and/or other materials provided with the + * distribution. + * 3. Neither the name PX4 nor the names of its contributors may be + * used to endorse or promote products derived from this software + * without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS + * OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED + * AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + * + ****************************************************************************/ + +/** + * @file bmp388_spi.cpp + * + * SPI interface for BMP388 + */ + +#include "bmp388.h" + + +/* SPI protocol address bits */ +#define DIR_READ (1<<7) //for set +#define DIR_WRITE ~(1<<7) //for clear + +#if defined(PX4_SPIDEV_BARO) || defined(PX4_SPIDEV_EXT_BARO) + +#pragma pack(push,1) +struct spi_data_s { + uint8_t addr; + struct bmp388::data_s data; +}; + +struct spi_calibration_s { + uint8_t addr; + struct bmp388::calibration_s cal; +}; +#pragma pack(pop) + +class BMP388_SPI: public device::SPI, public bmp388::IBMP388 +{ +public: + BMP388_SPI(uint8_t bus, uint32_t device, bool is_external_device); + virtual ~BMP388_SPI() = default; + + bool is_external(); + int init(); + + uint8_t get_reg(uint8_t addr); + int set_reg(uint8_t value, uint8_t addr); + bmp388::data_s *get_data(uint8_t addr); + bmp388::calibration_s *get_calibration(uint8_t addr); + + uint32_t get_device_id() const override { return device::SPI::get_device_id(); } + +private: + spi_calibration_s _cal; + spi_data_s _data; + bool _external; +}; + +bmp388::IBMP388 *bmp388_spi_interface(uint8_t busnum, uint32_t device, bool external) +{ + return new BMP388_SPI(busnum, device, external); +} + +BMP388_SPI::BMP388_SPI(uint8_t bus, uint32_t device, bool is_external_device) : + SPI("BMP388_SPI", nullptr, bus, device, SPIDEV_MODE3, 10 * 1000 * 1000) +{ + _external = is_external_device; +} + +bool BMP388_SPI::is_external() +{ + return _external; +}; + +int BMP388_SPI::init() +{ + return SPI::init(); +}; + +uint8_t BMP388_SPI::get_reg(uint8_t addr) +{ + uint8_t cmd[2] = { (uint8_t)(addr | DIR_READ), 0}; //set MSB bit + transfer(&cmd[0], &cmd[0], 2); + + return cmd[1]; +} + +int BMP388_SPI::set_reg(uint8_t value, uint8_t addr) +{ + uint8_t cmd[2] = { (uint8_t)(addr & DIR_WRITE), value}; //clear MSB bit + return transfer(&cmd[0], nullptr, 2); +} + +bmp388::data_s *BMP388_SPI::get_data(uint8_t addr) +{ + _data.addr = (uint8_t)(addr | DIR_READ); //set MSB bit + + if (transfer((uint8_t *)&_data, (uint8_t *)&_data, sizeof(struct spi_data_s)) == OK) { + return &(_data.data); + + } else { + return nullptr; + } +} + +bmp388::calibration_s *BMP388_SPI::get_calibration(uint8_t addr) +{ + _cal.addr = addr | DIR_READ; + + if (transfer((uint8_t *)&_cal, (uint8_t *)&_cal, sizeof(struct spi_calibration_s)) == OK) { + return &(_cal.cal); + + } else { + return nullptr; + } +} + +#endif /* PX4_SPIDEV_BARO || PX4_SPIDEV_EXT_BARO */ diff --git a/src/drivers/barometer/bmp388/bmp3_defs.h b/src/drivers/barometer/bmp388/bmp3_defs.h new file mode 100644 index 000000000000..af8365453d5e --- /dev/null +++ b/src/drivers/barometer/bmp388/bmp3_defs.h @@ -0,0 +1,761 @@ +/** + * Copyright (C) 2018 - 2019 Bosch Sensortec GmbH + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions are met: + * + * Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * + * Redistributions in binary form must reproduce the above copyright + * notice, this list of conditions and the following disclaimer in the + * documentation and/or other materials provided with the distribution. + * + * Neither the name of the copyright holder nor the names of the + * contributors may be used to endorse or promote products derived from + * this software without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND + * CONTRIBUTORS "AS IS" AND ANY EXPRESS OR + * IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED + * WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE + * DISCLAIMED. IN NO EVENT SHALL COPYRIGHT HOLDER + * OR CONTRIBUTORS BE LIABLE FOR ANY + * DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, + * OR CONSEQUENTIAL DAMAGES(INCLUDING, BUT NOT LIMITED TO, + * PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; + * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) + * HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, + * WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT + * (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS + * SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE + * + * The information provided is believed to be accurate and reliable. + * The copyright holder assumes no responsibility + * for the consequences of use + * of such information nor for any infringement of patents or + * other rights of third parties which may result from its use. + * No license is granted by implication or otherwise under any patent or + * patent rights of the copyright holder. + * + * @file bmp3_defs.h + * @date 01 July 2019 + * @version 1.1.3 + * @brief + * + */ + +/*! @file bmp3_defs.h + * @brief Sensor driver for BMP3 sensor */ + +/*! + * @defgroup BMP3 SENSOR API + * @brief + * @{*/ +#ifndef BMP3_DEFS_H_ +#define BMP3_DEFS_H_ + +/*! CPP guard */ +#ifdef __cplusplus +extern "C" { +#endif + +/********************************************************/ +/**\name Compiler switch macros */ +/**\name Uncomment the below line to use floating-point compensation */ +#ifndef BMP3_DOUBLE_PRECISION_COMPENSATION + +/* #define BMP3_DOUBLE_PRECISION_COMPENSATION*/ +#endif + +/********************************************************/ +/**\name Macro definitions */ +/**\name I2C addresses */ +#define BMP3_I2C_ADDR_PRIM (0x76) +#define BMP3_I2C_ADDR_SEC (0x77) + +/**\name BMP3 chip identifier */ +#define BMP3_CHIP_ID (0x50) + +/**\name BMP3 pressure settling time (micro secs)*/ +#define BMP3_PRESS_SETTLE_TIME (392) + +/**\name BMP3 temperature settling time (micro secs) */ +#define BMP3_TEMP_SETTLE_TIME (313) + +/**\name BMP3 adc conversion time (micro secs) */ +#define BMP3_ADC_CONV_TIME (2000) + +/**\name Register Address */ +#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_EVENT_ADDR (0x10) +#define BMP3_INT_STATUS_REG_ADDR (0x11) +#define BMP3_FIFO_LENGTH_ADDR (0x12) +#define BMP3_FIFO_DATA_ADDR (0x14) +#define BMP3_FIFO_WM_ADDR (0x15) +#define BMP3_FIFO_CONFIG_1_ADDR (0x17) +#define BMP3_FIFO_CONFIG_2_ADDR (0x18) +#define BMP3_INT_CTRL_ADDR (0x19) +#define BMP3_IF_CONF_ADDR (0x1A) +#define BMP3_PWR_CTRL_ADDR (0x1B) +#define BMP3_OSR_ADDR (0X1C) +#define BMP3_CALIB_DATA_ADDR (0x31) +#define BMP3_CMD_ADDR (0x7E) + +/**\name Error status macros */ +#define BMP3_FATAL_ERR (0x01) +#define BMP3_CMD_ERR (0x02) +#define BMP3_CONF_ERR (0x04) + +/**\name Status macros */ +#define BMP3_CMD_RDY (0x10) +#define BMP3_DRDY_PRESS (0x20) +#define BMP3_DRDY_TEMP (0x40) + +/**\name Power mode macros */ +#define BMP3_SLEEP_MODE (0x00) +#define BMP3_FORCED_MODE (0x01) +#define BMP3_NORMAL_MODE (0x03) + +/**\name FIFO related macros */ +/**\name FIFO enable */ +#define BMP3_ENABLE (0x01) +#define BMP3_DISABLE (0x00) + +/**\name Interrupt pin configuration macros */ +/**\name Open drain */ +#define BMP3_INT_PIN_OPEN_DRAIN (0x01) +#define BMP3_INT_PIN_PUSH_PULL (0x00) + +/**\name Level */ +#define BMP3_INT_PIN_ACTIVE_HIGH (0x01) +#define BMP3_INT_PIN_ACTIVE_LOW (0x00) + +/**\name Latch */ +#define BMP3_INT_PIN_LATCH (0x01) +#define BMP3_INT_PIN_NON_LATCH (0x00) + +/**\name Advance settings */ +/**\name I2c watch dog timer period selection */ +#define BMP3_I2C_WDT_SHORT_1_25_MS (0x00) +#define BMP3_I2C_WDT_LONG_40_MS (0x01) + +/**\name FIFO Sub-sampling macros */ +#define BMP3_FIFO_NO_SUBSAMPLING (0x00) +#define BMP3_FIFO_SUBSAMPLING_2X (0x01) +#define BMP3_FIFO_SUBSAMPLING_4X (0x02) +#define BMP3_FIFO_SUBSAMPLING_8X (0x03) +#define BMP3_FIFO_SUBSAMPLING_16X (0x04) +#define BMP3_FIFO_SUBSAMPLING_32X (0x05) +#define BMP3_FIFO_SUBSAMPLING_64X (0x06) +#define BMP3_FIFO_SUBSAMPLING_128X (0x07) + +/**\name Over sampling macros */ +#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) + +/**\name Filter setting macros */ +#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) + +/**\name Odr setting macros */ +#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_ODR_12_5_HZ (0x04) +#define BMP3_ODR_6_25_HZ (0x05) +#define BMP3_ODR_3_1_HZ (0x06) +#define BMP3_ODR_1_5_HZ (0x07) +#define BMP3_ODR_0_78_HZ (0x08) +#define BMP3_ODR_0_39_HZ (0x09) +#define BMP3_ODR_0_2_HZ (0x0A) +#define BMP3_ODR_0_1_HZ (0x0B) +#define BMP3_ODR_0_05_HZ (0x0C) +#define BMP3_ODR_0_02_HZ (0x0D) +#define BMP3_ODR_0_01_HZ (0x0E) +#define BMP3_ODR_0_006_HZ (0x0F) +#define BMP3_ODR_0_003_HZ (0x10) +#define BMP3_ODR_0_001_HZ (0x11) + +/**\name API success code */ +#define BMP3_OK (0) + +/**\name API error codes */ +#define BMP3_E_NULL_PTR (-1) +#define BMP3_E_DEV_NOT_FOUND (-2) +#define BMP3_E_INVALID_ODR_OSR_SETTINGS (-3) +#define BMP3_E_CMD_EXEC_FAILED (-4) +#define BMP3_E_CONFIGURATION_ERR (-5) +#define BMP3_E_INVALID_LEN (-6) +#define BMP3_E_COMM_FAIL (-7) +#define BMP3_E_FIFO_WATERMARK_NOT_REACHED (-8) + +/**\name API warning codes */ +#define BMP3_W_SENSOR_NOT_ENABLED (1) +#define BMP3_W_INVALID_FIFO_REQ_FRAME_CNT (2) + +/**\name Macros to select the which sensor settings are to be set by the user. + * These values are internal for API implementation. Don't relate this to + * data sheet. */ +#define BMP3_PRESS_EN_SEL (1 << 1) +#define BMP3_TEMP_EN_SEL (1 << 2) +#define BMP3_DRDY_EN_SEL (1 << 3) +#define BMP3_PRESS_OS_SEL (1 << 4) +#define BMP3_TEMP_OS_SEL (1 << 5) +#define BMP3_IIR_FILTER_SEL (1 << 6) +#define BMP3_ODR_SEL (1 << 7) +#define BMP3_OUTPUT_MODE_SEL (1 << 8) +#define BMP3_LEVEL_SEL (1 << 9) +#define BMP3_LATCH_SEL (1 << 10) +#define BMP3_I2C_WDT_EN_SEL (1 << 11) +#define BMP3_I2C_WDT_SEL_SEL (1 << 12) +#define BMP3_ALL_SETTINGS (0x7FF) + +/**\name Macros to select the which FIFO settings are to be set by the user + * These values are internal for API implementation. Don't relate this to + * data sheet.*/ +#define BMP3_FIFO_MODE_SEL (1 << 1) +#define BMP3_FIFO_STOP_ON_FULL_EN_SEL (1 << 2) +#define BMP3_FIFO_TIME_EN_SEL (1 << 3) +#define BMP3_FIFO_PRESS_EN_SEL (1 << 4) +#define BMP3_FIFO_TEMP_EN_SEL (1 << 5) +#define BMP3_FIFO_DOWN_SAMPLING_SEL (1 << 6) +#define BMP3_FIFO_FILTER_EN_SEL (1 << 7) +#define BMP3_FIFO_FWTM_EN_SEL (1 << 8) +#define BMP3_FIFO_FULL_EN_SEL (1 << 9) +#define BMP3_FIFO_ALL_SETTINGS (0x3FF) + +/**\name Sensor component selection macros + * These values are internal for API implementation. Don't relate this to + * data sheet.*/ +#define BMP3_PRESS (1) +#define BMP3_TEMP (1 << 1) +#define BMP3_ALL (0x03) + +/**\name Macros for bit masking */ +#define BMP3_ERR_FATAL_MSK (0x01) + +#define BMP3_ERR_CMD_MSK (0x02) +#define BMP3_ERR_CMD_POS (0x01) + +#define BMP3_ERR_CONF_MSK (0x04) +#define BMP3_ERR_CONF_POS (0x02) + +#define BMP3_STATUS_CMD_RDY_MSK (0x10) +#define BMP3_STATUS_CMD_RDY_POS (0x04) + +#define BMP3_STATUS_DRDY_PRESS_MSK (0x20) +#define BMP3_STATUS_DRDY_PRESS_POS (0x05) + +#define BMP3_STATUS_DRDY_TEMP_MSK (0x40) +#define BMP3_STATUS_DRDY_TEMP_POS (0x06) + +#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_FIFO_MODE_MSK (0x01) + +#define BMP3_FIFO_STOP_ON_FULL_MSK (0x02) +#define BMP3_FIFO_STOP_ON_FULL_POS (0x01) + +#define BMP3_FIFO_TIME_EN_MSK (0x04) +#define BMP3_FIFO_TIME_EN_POS (0x02) + +#define BMP3_FIFO_PRESS_EN_MSK (0x08) +#define BMP3_FIFO_PRESS_EN_POS (0x03) + +#define BMP3_FIFO_TEMP_EN_MSK (0x10) +#define BMP3_FIFO_TEMP_EN_POS (0x04) + +#define BMP3_FIFO_FILTER_EN_MSK (0x18) +#define BMP3_FIFO_FILTER_EN_POS (0x03) + +#define BMP3_FIFO_DOWN_SAMPLING_MSK (0x07) + +#define BMP3_FIFO_FWTM_EN_MSK (0x08) +#define BMP3_FIFO_FWTM_EN_POS (0x03) + +#define BMP3_FIFO_FULL_EN_MSK (0x10) +#define BMP3_FIFO_FULL_EN_POS (0x04) + +#define BMP3_INT_OUTPUT_MODE_MSK (0x01) + +#define BMP3_INT_LEVEL_MSK (0x02) +#define BMP3_INT_LEVEL_POS (0x01) + +#define BMP3_INT_LATCH_MSK (0x04) +#define BMP3_INT_LATCH_POS (0x02) + +#define BMP3_INT_DRDY_EN_MSK (0x40) +#define BMP3_INT_DRDY_EN_POS (0x06) + +#define BMP3_I2C_WDT_EN_MSK (0x02) +#define BMP3_I2C_WDT_EN_POS (0x01) + +#define BMP3_I2C_WDT_SEL_MSK (0x04) +#define BMP3_I2C_WDT_SEL_POS (0x02) + +#define BMP3_INT_STATUS_FWTM_MSK (0x01) + +#define BMP3_INT_STATUS_FFULL_MSK (0x02) +#define BMP3_INT_STATUS_FFULL_POS (0x01) + +#define BMP3_INT_STATUS_DRDY_MSK (0x08) +#define BMP3_INT_STATUS_DRDY_POS (0x03) + +/**\name UTILITY MACROS */ +#define BMP3_SET_LOW_BYTE (0x00FF) +#define BMP3_SET_HIGH_BYTE (0xFF00) + +/**\name Macro to combine two 8 bit data's to form a 16 bit data */ +#define BMP3_CONCAT_BYTES(msb, lsb) (((uint16_t)msb << 8) | (uint16_t)lsb) + +#define BMP3_SET_BITS(reg_data, bitname, data) \ + ((reg_data & ~(bitname##_MSK)) | \ + ((data << bitname##_POS) & bitname##_MSK)) + +/* Macro variant to handle the bitname position if it is zero */ +#define BMP3_SET_BITS_POS_0(reg_data, bitname, data) \ + ((reg_data & ~(bitname##_MSK)) | \ + (data & bitname##_MSK)) + +#define BMP3_GET_BITS(reg_data, bitname) ((reg_data & (bitname##_MSK)) >> \ + (bitname##_POS)) + +/* Macro variant to handle the bitname position if it is zero */ +#define BMP3_GET_BITS_POS_0(reg_data, bitname) (reg_data & (bitname##_MSK)) + +#define BMP3_GET_LSB(var) (uint8_t)(var & BMP3_SET_LOW_BYTE) +#define BMP3_GET_MSB(var) (uint8_t)((var & BMP3_SET_HIGH_BYTE) >> 8) + +/**\name Macros related to size */ +#define BMP3_CALIB_DATA_LEN (21) +#define BMP3_P_AND_T_HEADER_DATA_LEN (7) +#define BMP3_P_OR_T_HEADER_DATA_LEN (4) +#define BMP3_P_T_DATA_LEN (6) +#define BMP3_GEN_SETT_LEN (7) +#define BMP3_P_DATA_LEN (3) +#define BMP3_T_DATA_LEN (3) +#define BMP3_SENSOR_TIME_LEN (3) +#define BMP3_FIFO_MAX_FRAMES (73) + +/********************************************************/ + +/*! + * @brief Interface selection Enums + */ +enum bmp3_intf { + /*! SPI interface */ + BMP3_SPI_INTF, + + /*! I2C interface */ + BMP3_I2C_INTF +}; + +/********************************************************/ + +/*! + * @brief Type definitions + */ +typedef int8_t (*bmp3_com_fptr_t)(uint8_t dev_id, uint8_t reg_addr, uint8_t *data, uint16_t len); +typedef void (*bmp3_delay_fptr_t)(uint32_t period); + +/********************************************************/ + +/*! + * @brief Register Trim Variables + */ +#pragma pack(push,1) +struct bmp3_reg_calib_data { + /** + * @ Trim Variables + */ + + /**@{*/ + uint16_t par_t1; + uint16_t par_t2; + int8_t par_t3; + int16_t par_p1; + int16_t par_p2; + int8_t par_p3; + int8_t par_p4; + uint16_t par_p5; + uint16_t par_p6; + int8_t par_p7; + int8_t par_p8; + int16_t par_p9; + int8_t par_p10; + int8_t par_p11; + int64_t t_lin; + + /**@}*/ +}; +#pragma pack(pop) + +/*! + * @brief bmp3 advance settings + */ +struct bmp3_adv_settings { + /*! i2c watch dog enable */ + uint8_t i2c_wdt_en; + + /*! i2c watch dog select */ + uint8_t i2c_wdt_sel; +}; + +/*! + * @brief bmp3 odr and filter settings + */ +struct bmp3_odr_filter_settings { + /*! Pressure oversampling */ + uint8_t press_os; + + /*! Temperature oversampling */ + uint8_t temp_os; + + /*! IIR filter */ + uint8_t iir_filter; + + /*! Output data rate */ + uint8_t odr; +}; + +/*! + * @brief bmp3 sensor status flags + */ +struct bmp3_sens_status { + /*! Command ready status */ + uint8_t cmd_rdy; + + /*! Data ready for pressure */ + uint8_t drdy_press; + + /*! Data ready for temperature */ + uint8_t drdy_temp; +}; + +/*! + * @brief bmp3 interrupt status flags + */ +struct bmp3_int_status { + /*! fifo watermark interrupt */ + uint8_t fifo_wm; + + /*! fifo full interrupt */ + uint8_t fifo_full; + + /*! data ready interrupt */ + uint8_t drdy; +}; + +/*! + * @brief bmp3 error status flags + */ +struct bmp3_err_status { + /*! fatal error */ + uint8_t fatal; + + /*! command error */ + uint8_t cmd; + + /*! configuration error */ + uint8_t conf; +}; + +/*! + * @brief bmp3 status flags + */ +struct bmp3_status { + /*! Interrupt status */ + struct bmp3_int_status intr; + + /*! Sensor status */ + struct bmp3_sens_status sensor; + + /*! Error status */ + struct bmp3_err_status err; + + /*! power on reset status */ + uint8_t pwr_on_rst; +}; + +/*! + * @brief bmp3 interrupt pin settings + */ +struct bmp3_int_ctrl_settings { + /*! Output mode */ + uint8_t output_mode; + + /*! Active high/low */ + uint8_t level; + + /*! Latched or Non-latched */ + uint8_t latch; + + /*! Data ready interrupt */ + uint8_t drdy_en; +}; + +/*! + * @brief bmp3 device settings + */ +struct bmp3_settings { + /*! Power mode which user wants to set */ + uint8_t op_mode; + + /*! Enable/Disable pressure sensor */ + uint8_t press_en; + + /*! Enable/Disable temperature sensor */ + uint8_t temp_en; + + /*! ODR and filter configuration */ + struct bmp3_odr_filter_settings odr_filter; + + /*! Interrupt configuration */ + struct bmp3_int_ctrl_settings int_settings; + + /*! Advance settings */ + struct bmp3_adv_settings adv_settings; +}; + +/*! + * @brief bmp3 fifo frame + */ +struct bmp3_fifo_data { + /*! Data buffer of user defined length is to be mapped here + * 512 + 4 */ + uint8_t buffer[516]; + + /*! Number of bytes of data read from the fifo */ + uint16_t byte_count; + + /*! Number of frames to be read as specified by the user */ + uint8_t req_frames; + + /*! Will be equal to length when no more frames are there to parse */ + uint16_t start_idx; + + /*! Will contain the no of parsed data frames from fifo */ + uint8_t parsed_frames; + + /*! Configuration error */ + uint8_t config_err; + + /*! Sensor time */ + uint32_t sensor_time; + + /*! FIFO input configuration change */ + uint8_t config_change; + + /*! All available frames are parsed */ + uint8_t frame_not_available; +}; + +/*! + * @brief bmp3 fifo configuration + */ +struct bmp3_fifo_settings { + /*! enable/disable */ + uint8_t mode; + + /*! stop on full enable/disable */ + uint8_t stop_on_full_en; + + /*! time enable/disable */ + uint8_t time_en; + + /*! pressure enable/disable */ + uint8_t press_en; + + /*! temperature enable/disable */ + uint8_t temp_en; + + /*! down sampling rate */ + uint8_t down_sampling; + + /*! filter enable/disable */ + uint8_t filter_en; + + /*! FIFO watermark enable/disable */ + uint8_t fwtm_en; + + /*! FIFO full enable/disable */ + uint8_t ffull_en; +}; + +/*! + * @brief bmp3 bmp3 FIFO + */ +struct bmp3_fifo { + /*! FIFO frame structure */ + struct bmp3_fifo_data data; + + /*! FIFO config structure */ + struct bmp3_fifo_settings settings; +}; + +#ifdef BMP3_DOUBLE_PRECISION_COMPENSATION + +/*! + * @brief Quantized Trim Variables + */ +struct bmp3_quantized_calib_data { + /** + * @ Quantized Trim Variables + */ + + /**@{*/ + double par_t1; + double par_t2; + double par_t3; + double par_p1; + double par_p2; + double par_p3; + double par_p4; + double par_p5; + double par_p6; + double par_p7; + double par_p8; + double par_p9; + double par_p10; + double par_p11; + double t_lin; + + /**@}*/ +}; + +/*! + * @brief Calibration data + */ +struct bmp3_calib_data { + /*! Quantized data */ + struct bmp3_quantized_calib_data quantized_calib_data; + + /*! Register data */ + struct bmp3_reg_calib_data reg_calib_data; +}; + +/*! + * @brief bmp3 sensor structure which comprises of temperature and pressure + * data. + */ +struct bmp3_data { + /*! Compensated temperature */ + double temperature; + + /*! Compensated pressure */ + double pressure; +}; + +#else + +/*! + * @brief bmp3 sensor structure which comprises of temperature and pressure + * data. + */ +struct bmp3_data { + /*! Compensated temperature */ + int64_t temperature; + + /*! Compensated pressure */ + uint64_t pressure; +}; + +/*! + * @brief Calibration data + */ +struct bmp3_calib_data { + /*! Register data */ + struct bmp3_reg_calib_data reg_calib_data; +}; + +#endif /* BMP3_DOUBLE_PRECISION_COMPENSATION */ + +/*! + * @brief bmp3 sensor structure which comprises of un-compensated temperature + * and pressure data. + */ +struct bmp3_uncomp_data { + /*! un-compensated pressure */ + uint32_t pressure; + + /*! un-compensated temperature */ + uint32_t temperature; +}; + +/*! + * @brief bmp3 device structure + */ +struct bmp3_dev { + /*! Chip Id */ + uint8_t chip_id; + + /*! Device Id */ + uint8_t dev_id; + + /*! SPI/I2C interface */ + enum bmp3_intf intf; + + /*! Decide SPI or I2C read mechanism */ + uint8_t dummy_byte; + + /*! Read function pointer */ + bmp3_com_fptr_t read; + + /*! Write function pointer */ + bmp3_com_fptr_t write; + + /*! Delay function pointer */ + bmp3_delay_fptr_t delay_ms; + + /*! Trim data */ + struct bmp3_calib_data calib_data; + + /*! Sensor Settings */ + struct bmp3_settings settings; + + /*! Sensor and interrupt status flags */ + struct bmp3_status status; + + /*! FIFO data and settings structure */ + struct bmp3_fifo *fifo; +}; + +#ifdef __cplusplus +} +#endif /* End of CPP guard */ + +#endif /* BMP3_DEFS_H_ */ +/** @}*/ +/** @}*/ diff --git a/src/drivers/drv_sensor.h b/src/drivers/drv_sensor.h index f93216621e82..769102dc765e 100644 --- a/src/drivers/drv_sensor.h +++ b/src/drivers/drv_sensor.h @@ -115,6 +115,7 @@ #define DRV_GYR_DEVTYPE_ADIS16497 0x64 #define DRV_BARO_DEVTYPE_BAROSIM 0x65 #define DRV_DEVTYPE_BMI088 0x66 +#define DRV_DEVTYPE_BMP388 0x67 /* * ioctl() definitions diff --git a/src/lib/drivers/barometer/PX4Barometer.hpp b/src/lib/drivers/barometer/PX4Barometer.hpp index ca48928119a3..dcef8bd1a4ad 100644 --- a/src/lib/drivers/barometer/PX4Barometer.hpp +++ b/src/lib/drivers/barometer/PX4Barometer.hpp @@ -45,7 +45,7 @@ class PX4Barometer : public cdev::CDev { public: - PX4Barometer(uint32_t device_id, uint8_t priority); + PX4Barometer(uint32_t device_id, uint8_t priority = ORB_PRIO_DEFAULT); ~PX4Barometer() override; void set_device_type(uint8_t devtype);