Skip to content

Commit

Permalink
Add BMP390 to BMP388 driver
Browse files Browse the repository at this point in the history
  • Loading branch information
AlexKlimaj authored and dagar committed Sep 21, 2022
1 parent 8cfc4fc commit 61d2b13
Show file tree
Hide file tree
Showing 4 changed files with 32 additions and 3 deletions.
13 changes: 11 additions & 2 deletions src/drivers/barometer/bmp388/bmp388.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -68,11 +68,19 @@ BMP388::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);
_chip_id = _interface->get_reg(BMP3_CHIP_ID_ADDR);

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);
return -EIO;
}

if (_chip_id == BMP390_CHIP_ID) {
_interface->set_device_type(DRV_BARO_DEVTYPE_BMP390);
}

_chip_rev_id = _interface->get_reg(BMP3_REV_ID_ADDR);

_cal = _interface->get_calibration(BMP3_CALIB_DATA_ADDR);

if (!_cal) {
Expand All @@ -99,6 +107,7 @@ void
BMP388::print_status()
{
I2CSPIDriverBase::print_status();
printf("chip id: 0x%02x rev id: 0x%02x\n", _chip_id, _chip_rev_id);
perf_print_counter(_sample_perf);
perf_print_counter(_measure_perf);
perf_print_counter(_comms_errors);
Expand Down
9 changes: 8 additions & 1 deletion src/drivers/barometer/bmp388/bmp388.h
Original file line number Diff line number Diff line change
Expand Up @@ -51,7 +51,8 @@

// From https://github.com/BoschSensortec/BMP3-Sensor-API/blob/master/bmp3_defs.h

#define BMP3_CHIP_ID (0x50)
#define BMP388_CHIP_ID (0x50)
#define BMP390_CHIP_ID (0x60)

/* Over sampling macros */
#define BMP3_NO_OVERSAMPLING (0x00)
Expand Down Expand Up @@ -79,6 +80,7 @@

/* Register Address */
#define BMP3_CHIP_ID_ADDR (0x00)
#define BMP3_REV_ID_ADDR (0x01)
#define BMP3_ERR_REG_ADDR (0x02)
#define BMP3_SENS_STATUS_REG_ADDR (0x03)
#define BMP3_DATA_ADDR (0x04)
Expand Down Expand Up @@ -304,6 +306,8 @@ class IBMP388
virtual uint32_t get_device_id() const = 0;

virtual uint8_t get_device_address() const = 0;

virtual void set_device_type(uint8_t devtype) = 0;
};

class BMP388 : public I2CSPIDriver<BMP388>
Expand Down Expand Up @@ -339,6 +343,9 @@ class BMP388 : public I2CSPIDriver<BMP388>

bool _collect_phase{false};

uint8_t _chip_id{0};
uint8_t _chip_rev_id{0};

void start();
int measure();
int collect(); //get results and publish
Expand Down
6 changes: 6 additions & 0 deletions src/drivers/barometer/bmp388/bmp388_i2c.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -58,6 +58,7 @@ class BMP388_I2C: public device::I2C, public IBMP388

uint8_t get_device_address() const override { return device::I2C::get_device_address(); }

void set_device_type(uint8_t devtype);
private:
struct calibration_s _cal;
};
Expand Down Expand Up @@ -108,3 +109,8 @@ calibration_s *BMP388_I2C::get_calibration(uint8_t addr)
return nullptr;
}
}

void BMP388_I2C::set_device_type(uint8_t devtype)
{
device::Device::set_device_type(devtype);
}
7 changes: 7 additions & 0 deletions src/drivers/barometer/bmp388/bmp388_spi.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -74,6 +74,8 @@ class BMP388_SPI: public device::SPI, public IBMP388
uint32_t get_device_id() const override { return device::SPI::get_device_id(); }

uint8_t get_device_address() const override { return device::SPI::get_device_address(); }

void set_device_type(uint8_t devtype);
private:
spi_calibration_s _cal;
};
Expand Down Expand Up @@ -124,3 +126,8 @@ calibration_s *BMP388_SPI::get_calibration(uint8_t addr)
return nullptr;
}
}

void BMP388_SPI::set_device_type(uint8_t devtype)
{
device::Device::set_device_type(devtype);
}

0 comments on commit 61d2b13

Please sign in to comment.