diff --git a/boards/px4/fmu-v5/stackcheck.cmake b/boards/px4/fmu-v5/stackcheck.cmake index 8f4a733080a6..83ddb3d6f1a8 100644 --- a/boards/px4/fmu-v5/stackcheck.cmake +++ b/boards/px4/fmu-v5/stackcheck.cmake @@ -19,7 +19,7 @@ px4_add_board( DRIVERS adc - barometer # all available barometer drivers + barometer/ms5611 batt_smbus camera_capture camera_trigger 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..f4e09193d41c --- /dev/null +++ b/src/drivers/barometer/bmp388/CMakeLists.txt @@ -0,0 +1,49 @@ +############################################################################ +# +# 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 + bmp388_main.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..6147ac97e432 --- /dev/null +++ b/src/drivers/barometer/bmp388/bmp388.cpp @@ -0,0 +1,629 @@ +/**************************************************************************** + * + * 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). + * + * Refer to: https://github.com/BoschSensortec/BMP3-Sensor-API + */ + +#include "bmp388.h" + +BMP388::BMP388(IBMP388 *interface, const char *path) : + CDev(path), + ScheduledWorkItem(MODULE_NAME, px4::device_bus_to_wq(interface->get_device_id())), + _px4_baro(interface->get_device_id(), ORB_PRIO_DEFAULT), + _interface(interface), + _osr_t(BMP3_OVERSAMPLING_2X), + _osr_p(BMP3_OVERSAMPLING_16X), + _odr(BMP3_ODR_50_HZ), + _iir_coef(BMP3_IIR_FILTER_DISABLE), + _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")), + _collect_phase(false) +{ + _px4_baro.set_device_type(DRV_DEVTYPE_BMP388); +} + +BMP388::~BMP388() +{ + /* make sure we are truly inactive */ + stop(); + + /* free perf counters */ + perf_free(_sample_perf); + perf_free(_measure_perf); + perf_free(_comms_errors); + + delete _interface; +} + +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; + } + + /* sleep this first time around */ + px4_usleep(_measure_interval); + + if (collect()) { + return -EIO; + } + + start(); + + return OK; +} + +void +BMP388::print_info() +{ + perf_print_counter(_sample_perf); + perf_print_counter(_measure_perf); + perf_print_counter(_comms_errors); + printf("measurement interval: %u us \n", _measure_interval); + + _px4_baro.print_status(); +} + +void +BMP388::start() +{ + _collect_phase = false; + + /* make sure we are stopped first */ + stop(); + + ScheduleOnInterval(_measure_interval, 1000); +} + +void +BMP388::stop() +{ + ScheduleClear(); +} + +/* + * ScheduledWorkItem override + */ +void +BMP388::Run() +{ + if (_collect_phase) { + collect(); + } + + measure(); +} + +int +BMP388::measure() +{ + _collect_phase = true; + + perf_begin(_measure_perf); + + /* start measurement */ + 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() +{ + _collect_phase = false; + + /* enable pressure and temperature */ + uint8_t sensor_comp = BMP3_PRESS | BMP3_TEMP; + bmp3_data data{}; + + 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(); + + 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)); + + float temperature = (float)(data.temperature / 100.0f); + float pressure = (float)(data.pressure / 100.0f); // to hecto Pascal + pressure = pressure / 100.0f; // to mbar + + _px4_baro.set_temperature(temperature); + _px4_baro.update(timestamp_sample, pressure); // to mbar + + perf_end(_sample_perf); + + return OK; +} + +/*! + * @brief This API performs the soft reset of the sensor. + * + * Refer: https://github.com/BoschSensortec/BMP3-Sensor-API/blob/master/bmp3.c + */ +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 + * + * Refer: 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 + * + * Refer: 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[BMP3_CALIB_DATA_LEN]; + uint8_t i; + + memcpy(&trim_param, _cal, BMP3_CALIB_DATA_LEN); + + for (i = 0; i < BMP3_CALIB_DATA_LEN; 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; +} + +uint32_t +BMP388::get_measurement_time(uint8_t osr_t, uint8_t osr_p) +{ + /* + From BST-BMP388-DS001.pdf, page 25, table 21 + + Pressure Temperature Measurement Max Time + Oversample Oversample Time (Forced) + x1 1x 4.9 ms 5.7 ms + x2 1x 6.9 ms 8.7 ms + x4 1x 10.9 ms 13.3 ms + x8 1x 18.9 ms 22.5 ms + x16 2x 36.9 ms 43.3 ms + x32 2x 68.9 ms (not documented) + */ + + uint32_t meas_time_us = 0; // unsupported value by default + + if (osr_t == BMP3_NO_OVERSAMPLING) { + switch (osr_p) { + case BMP3_NO_OVERSAMPLING: + meas_time_us = 5700; + break; + + case BMP3_OVERSAMPLING_2X: + meas_time_us = 8700; + break; + + case BMP3_OVERSAMPLING_4X: + meas_time_us = 13300; + break; + + case BMP3_OVERSAMPLING_8X: + meas_time_us = 22500; + break; + } + + } else if (osr_t == BMP3_OVERSAMPLING_2X) { + switch (osr_p) { + case BMP3_OVERSAMPLING_16X: + meas_time_us = 43300; + break; + + case BMP3_OVERSAMPLING_32X: + meas_time_us = 68900; + break; + } + } + + return meas_time_us; +} + +/*! + * @brief This API sets the power control(pressure enable and + * temperature enable), over sampling, odr and filter + * settings in the sensor. + * + * Refer: https://github.com/BoschSensortec/BMP3-Sensor-API/blob/master/bmp3.c + */ +bool +BMP388::set_sensor_settings() +{ + _measure_interval = get_measurement_time(_osr_t, _osr_p); + + if (_measure_interval == 0) { + PX4_WARN("unsupported oversampling selected"); + return false; + } + + /* 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); + + int 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 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, _osr_p); + osr_ctl_reg = BMP3_SET_BITS(osr_ctl_reg, BMP3_TEMP_OS, _osr_t); + + ret = _interface->set_reg(osr_ctl_reg, BMP3_OSR_ADDR); + + if (ret != OK) { + PX4_WARN("failed to set settings BMP3_OSR_ADDR"); + return false; + } + + /* Using 'forced mode' so this is not required but here for future use possibly */ + uint8_t odr_ctl_reg = 0; + odr_ctl_reg = BMP3_SET_BITS_POS_0(odr_ctl_reg, BMP3_ODR, _odr); + + ret = _interface->set_reg(odr_ctl_reg, BMP3_ODR_ADDR); + + if (ret != OK) { + PX4_WARN("failed to set output data rate register"); + return false; + } + + uint8_t iir_ctl_reg = 0; + iir_ctl_reg = BMP3_SET_BITS(iir_ctl_reg, BMP3_IIR_FILTER, _iir_coef); + ret = _interface->set_reg(iir_ctl_reg, BMP3_IIR_ADDR); + + if (ret != OK) { + PX4_WARN("failed to set IIR settings"); + return false; + } + + return true; +} + + +/*! + * @brief This API sets the power mode of the sensor. + * + * Refer: https://github.com/BoschSensortec/BMP3-Sensor-API/blob/master/bmp3.c + */ +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); + + /* Device needs to be put in sleep mode to transition */ + if (last_set_mode != BMP3_SLEEP_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. + * + * Refer: https://github.com/BoschSensortec/BMP3-Sensor-API/blob/master/bmp3.c + */ +static void parse_sensor_data(const uint8_t *reg_data, struct bmp3_uncomp_data *uncomp_data) +{ + uint32_t data_xlsb; + uint32_t data_lsb; + uint32_t data_msb; + + 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; + + 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 + * + * Refer: https://github.com/BoschSensortec/BMP3-Sensor-API/blob/master/bmp3.c + */ +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 + * + * Refer: https://github.com/BoschSensortec/BMP3-Sensor-API/blob/master/bmp3.c + */ +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. + * + * Refer: https://github.com/BoschSensortec/BMP3-Sensor-API/blob/master/bmp3.c + */ +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) { + 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; + + uint8_t reg_data[BMP3_P_T_DATA_LEN] = { 0 }; + struct bmp3_uncomp_data uncomp_data = { 0 }; + + rslt = _interface->get_reg_buf(BMP3_DATA_ADDR, reg_data, BMP3_P_T_DATA_LEN); + + if (rslt == OK) { + parse_sensor_data(reg_data, &uncomp_data); + result = compensate_data(sensor_comp, &uncomp_data, comp_data); + } + + return result; +} diff --git a/src/drivers/barometer/bmp388/bmp388.h b/src/drivers/barometer/bmp388/bmp388.h new file mode 100644 index 000000000000..cbfbc70dbd03 --- /dev/null +++ b/src/drivers/barometer/bmp388/bmp388.h @@ -0,0 +1,365 @@ +/**************************************************************************** + * + * 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 "board_config.h" + +// From https://github.com/BoschSensortec/BMP3-Sensor-API/blob/master/bmp3_defs.h + +#define BMP3_CHIP_ID (0x50) + +/* 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) + +/* 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) + +/* 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) + +/* 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_PWR_CTRL_ADDR (0x1B) +#define BMP3_OSR_ADDR (0X1C) +#define BMP3_CALIB_DATA_ADDR (0x31) +#define BMP3_CMD_ADDR (0x7E) + +/* Error status macros */ +#define BMP3_FATAL_ERR (0x01) +#define BMP3_CMD_ERR (0x02) +#define BMP3_CONF_ERR (0x04) + +/* Status macros */ +#define BMP3_CMD_RDY (0x10) +#define BMP3_DRDY_PRESS (0x20) +#define BMP3_DRDY_TEMP (0x40) + +/* Power mode macros */ +#define BMP3_SLEEP_MODE (0x00) +#define BMP3_FORCED_MODE (0x01) +#define BMP3_NORMAL_MODE (0x03) + +#define BMP3_ENABLE (0x01) +#define BMP3_DISABLE (0x00) + +/* Sensor component selection macros. These values are internal for API implementation. + * Don't relate this t0 data sheet. + */ +#define BMP3_PRESS (1) +#define BMP3_TEMP (1 << 1) +#define BMP3_ALL (0x03) + +/* Macros related to size */ +#define BMP3_CALIB_DATA_LEN (21) +#define BMP3_P_T_DATA_LEN (6) + +/* 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_PRESS_OS_SEL (1 << 4) + +/* Macros for bit masking */ +#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) \ + ((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)) + +// 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 +#define BMP3_ODR_ADDR 0x1D +#define BMP3_IIR_ADDR 0x1F + +// 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) + +#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 + +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) + +/*! + * bmp3 sensor structure which comprises of temperature and pressure data. + */ +struct bmp3_data { + /* Compensated temperature */ + int64_t temperature; + + /* Compensated pressure */ + uint64_t pressure; +}; + +/*! + * Calibration data + */ +struct bmp3_calib_data { + /*! Register data */ + struct bmp3_reg_calib_data reg_calib_data; +}; + +/*! + * 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; +}; + +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; +}; + +/* + * BMP388 internal constants and data structures. + */ + + +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 data_s *get_data(uint8_t addr) = 0; + + // bulk read of calibration data into buffer, return same pointer + virtual calibration_s *get_calibration(uint8_t addr) = 0; + + virtual uint32_t get_device_id() const = 0; + +}; + +class BMP388 : public cdev::CDev, public px4::ScheduledWorkItem +{ +public: + 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; + IBMP388 *_interface; + + unsigned _measure_interval{0}; // interval in microseconds needed to measure + uint8_t _osr_t; // oversampling rate, temperature + uint8_t _osr_p; // oversampling rate, pressure + uint8_t _odr; // output data rate + uint8_t _iir_coef; // IIR coefficient + + perf_counter_t _sample_perf; + perf_counter_t _measure_perf; + perf_counter_t _comms_errors; + + struct calibration_s *_cal; // stored calibration constants + + bool _collect_phase; + + void Run() override; + void start(); + void stop(); + int measure(); + int collect(); //get results and publish + uint32_t get_measurement_time(uint8_t osr_t, uint8_t osr_p); + + 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); +}; + + +/* interface factories */ +extern IBMP388 *bmp388_spi_interface(uint8_t busnum, uint32_t device, bool external); +extern IBMP388 *bmp388_i2c_interface(uint8_t busnum, uint32_t device, bool external); +typedef 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..354289ed3c38 --- /dev/null +++ b/src/drivers/barometer/bmp388/bmp388_i2c.cpp @@ -0,0 +1,134 @@ +/**************************************************************************** + * + * 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_i2c.cpp + * + * I2C interface for BMP388 + */ + +#include + +#include "bmp388.h" + +#if defined(PX4_I2C_OBDEV_BMP388) || defined(PX4_I2C_EXT_OBDEV_BMP388) + +class BMP388_I2C: public device::I2C, public 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); + data_s *get_data(uint8_t addr); + calibration_s *get_calibration(uint8_t addr); + + uint32_t get_device_id() const override { return device::I2C::get_device_id(); } + +private: + struct calibration_s _cal; + struct data_s _data; + bool _external; +}; + +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); +} + +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 data_s)) == OK) { + return (&_data); + + } else { + return nullptr; + } +} + +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 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_main.cpp b/src/drivers/barometer/bmp388/bmp388_main.cpp new file mode 100644 index 000000000000..5b3ccad30fe6 --- /dev/null +++ b/src/drivers/barometer/bmp388/bmp388_main.cpp @@ -0,0 +1,246 @@ +/**************************************************************************** + * + * 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. + * + ****************************************************************************/ + +#include + +#include "bmp388.h" + +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 +}; + +/** + * 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])) + +/** + * Start the driver. + */ +bool +start_bus(struct bmp388_bus_option &bus) +{ + if (bus.dev != nullptr) { + PX4_ERR("bus option already started"); + exit(1); + } + + 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; + } + + 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); +} + +/** + * 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 + +extern "C" __EXPORT 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' or 'info'"); + return -1; +} diff --git a/src/drivers/barometer/bmp388/bmp388_spi.cpp b/src/drivers/barometer/bmp388/bmp388_spi.cpp new file mode 100644 index 000000000000..818c11fb0c64 --- /dev/null +++ b/src/drivers/barometer/bmp388/bmp388_spi.cpp @@ -0,0 +1,151 @@ +/**************************************************************************** + * + * 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 (NOTE: untested!) + */ + +#include + +#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 data_s data; +}; + +struct spi_calibration_s { + uint8_t addr; + struct calibration_s cal; +}; +#pragma pack(pop) + +class BMP388_SPI: public device::SPI, public 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 get_reg_buf(uint8_t addr, uint8_t *buf, uint8_t len); + int set_reg(uint8_t value, uint8_t addr); + data_s *get_data(uint8_t addr); + 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; +}; + +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::get_reg_buf(uint8_t addr, uint8_t *buf, uint8_t len) +{ + uint8_t cmd[1] = {(uint8_t)(addr | DIR_READ)}; + return transfer(&cmd[0], buf, len); +} + +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); +} + +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; + } +} + +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/drv_sensor.h b/src/drivers/drv_sensor.h index 5f414f428ab4..aaad8d19515b 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