Skip to content

Commit

Permalink
bmp388: check bus return code after register read
Browse files Browse the repository at this point in the history
Check I2C/SPI bus transfer function return code after register
read operation.

Signed-off-by: Tero Salminen <[email protected]>
  • Loading branch information
t-salminen committed May 13, 2024
1 parent bac6101 commit 515f180
Show file tree
Hide file tree
Showing 4 changed files with 46 additions and 18 deletions.
40 changes: 33 additions & 7 deletions src/drivers/barometer/bmp388/bmp388.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -68,7 +68,10 @@ BMP388::init()
return -EIO;
}

_chip_id = _interface->get_reg(BMP3_CHIP_ID_ADDR);
if (_interface->get_reg(BMP3_CHIP_ID_ADDR, &_chip_id) != OK) {
PX4_WARN("failed to get chip id");
return -EIO;
}

if (_chip_id != BMP388_CHIP_ID && _chip_id != BMP390_CHIP_ID) {
PX4_WARN("id of your baro is not: 0x%02x or 0x%02x", BMP388_CHIP_ID, BMP390_CHIP_ID);
Expand All @@ -79,7 +82,10 @@ BMP388::init()
_interface->set_device_type(DRV_BARO_DEVTYPE_BMP390);
}

_chip_rev_id = _interface->get_reg(BMP3_REV_ID_ADDR);
if (_interface->get_reg(BMP3_REV_ID_ADDR, &_chip_rev_id) != OK) {
PX4_WARN("failed to get chip rev id");
return -EIO;
}

_cal = _interface->get_calibration(BMP3_CALIB_DATA_ADDR);

Expand Down Expand Up @@ -203,14 +209,22 @@ BMP388::soft_reset()
uint8_t status;
int ret;

status = _interface->get_reg(BMP3_SENS_STATUS_REG_ADDR);
ret = _interface->get_reg(BMP3_SENS_STATUS_REG_ADDR, &status);

if (ret != OK) {
return false;
}

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);
ret = _interface->get_reg(BMP3_ERR_REG_ADDR, &status);

if (ret != OK) {
return false;
}

if ((status & BMP3_CMD_ERR) == 0) {
result = true;
Expand Down Expand Up @@ -268,7 +282,9 @@ BMP388::validate_trimming_param()

crc = (crc ^ 0xFF);

stored_crc = _interface->get_reg(BMP3_TRIM_CRC_DATA_ADDR);
if (_interface->get_reg(BMP3_TRIM_CRC_DATA_ADDR, &stored_crc) != OK) {
return false;
}

return stored_crc == crc;
}
Expand Down Expand Up @@ -403,7 +419,12 @@ BMP388::set_op_mode(uint8_t op_mode)
uint8_t op_mode_reg_val;
int ret = OK;

op_mode_reg_val = _interface->get_reg(BMP3_PWR_CTRL_ADDR);
ret = _interface->get_reg(BMP3_PWR_CTRL_ADDR, &op_mode_reg_val);

if (ret != OK) {
return false;
}

last_set_mode = BMP3_GET_BITS(op_mode_reg_val, BMP3_OP_MODE);

/* Device needs to be put in sleep mode to transition */
Expand All @@ -419,7 +440,12 @@ BMP388::set_op_mode(uint8_t op_mode)
}

if (ret == OK) {
op_mode_reg_val = _interface->get_reg(BMP3_PWR_CTRL_ADDR);
ret = _interface->get_reg(BMP3_PWR_CTRL_ADDR, &op_mode_reg_val);

if (ret != OK) {
return false;
}

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);

Expand Down
2 changes: 1 addition & 1 deletion src/drivers/barometer/bmp388/bmp388.h
Original file line number Diff line number Diff line change
Expand Up @@ -292,7 +292,7 @@ class IBMP388
virtual int init() = 0;

// read reg value
virtual uint8_t get_reg(uint8_t addr) = 0;
virtual int get_reg(uint8_t addr, uint8_t *value) = 0;

// bulk read reg value
virtual int get_reg_buf(uint8_t addr, uint8_t *buf, uint8_t len) = 0;
Expand Down
10 changes: 4 additions & 6 deletions src/drivers/barometer/bmp388/bmp388_i2c.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -49,7 +49,7 @@ class BMP388_I2C: public device::I2C, public IBMP388

int init();

uint8_t get_reg(uint8_t addr);
int get_reg(uint8_t addr, uint8_t *value);
int get_reg_buf(uint8_t addr, uint8_t *buf, uint8_t len);
int set_reg(uint8_t value, uint8_t addr);
calibration_s *get_calibration(uint8_t addr);
Expand Down Expand Up @@ -78,12 +78,10 @@ int BMP388_I2C::init()
return I2C::init();
}

uint8_t BMP388_I2C::get_reg(uint8_t addr)
int BMP388_I2C::get_reg(uint8_t addr, uint8_t *value)
{
uint8_t cmd[2] = { (uint8_t)(addr), 0};
transfer(&cmd[0], 1, &cmd[1], 1);

return cmd[1];
const uint8_t cmd = (uint8_t)(addr);
return transfer(&cmd, sizeof(cmd), value, 1);
}

int BMP388_I2C::get_reg_buf(uint8_t addr, uint8_t *buf, uint8_t len)
Expand Down
12 changes: 8 additions & 4 deletions src/drivers/barometer/bmp388/bmp388_spi.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -66,7 +66,7 @@ class BMP388_SPI: public device::SPI, public IBMP388

int init();

uint8_t get_reg(uint8_t addr);
int get_reg(uint8_t addr, uint8_t *value);
int get_reg_buf(uint8_t addr, uint8_t *buf, uint8_t len);
int set_reg(uint8_t value, uint8_t addr);
calibration_s *get_calibration(uint8_t addr);
Expand Down Expand Up @@ -95,12 +95,16 @@ int BMP388_SPI::init()
return SPI::init();
};

uint8_t BMP388_SPI::get_reg(uint8_t addr)
int BMP388_SPI::get_reg(uint8_t addr, uint8_t *value)
{
uint8_t cmd[2] = { (uint8_t)(addr | DIR_READ), 0}; //set MSB bit
transfer(&cmd[0], &cmd[0], 2);
int ret = transfer(&cmd[0], &cmd[0], 2);

return cmd[1];
if (ret == OK) {
*value = cmd[1];
}

return ret;
}

int BMP388_SPI::get_reg_buf(uint8_t addr, uint8_t *buf, uint8_t len)
Expand Down

0 comments on commit 515f180

Please sign in to comment.