PX4 Firmware
PX4 Autopilot Software http://px4.io
BMP388 Class Reference

#include <bmp388.h>

Inheritance diagram for BMP388:
Collaboration diagram for BMP388:

Public Member Functions

 BMP388 (IBMP388 *interface)
 
virtual ~BMP388 ()
 
virtual int init ()
 
void print_info ()
 

Private Member Functions

void Run () override
 
void start ()
 
void stop ()
 
int measure ()
 
int collect ()
 
uint32_t get_measurement_time (uint8_t osr_t, uint8_t osr_p)
 
bool soft_reset ()
 This API performs the soft reset of the sensor. More...
 
bool get_calib_data ()
 
bool validate_trimming_param ()
 
bool set_sensor_settings ()
 This API sets the power control(pressure enable and temperature enable), over sampling, odr and filter settings in the sensor. More...
 
bool set_op_mode (uint8_t op_mode)
 This API sets the power mode of the sensor. More...
 
bool get_sensor_data (uint8_t sensor_comp, struct bmp3_data *comp_data)
 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. More...
 
bool compensate_data (uint8_t sensor_comp, const struct bmp3_uncomp_data *uncomp_data, struct bmp3_data *comp_data)
 This internal API is used to compensate the pressure or temperature or both the data according to the component selected by the user. More...
 

Private Attributes

PX4Barometer _px4_baro
 
IBMP388_interface {nullptr}
 
unsigned _measure_interval {0}
 
uint8_t _osr_t {BMP3_OVERSAMPLING_2X}
 
uint8_t _osr_p {BMP3_OVERSAMPLING_16X}
 
uint8_t _odr {BMP3_ODR_50_HZ}
 
uint8_t _iir_coef {BMP3_IIR_FILTER_DISABLE}
 
perf_counter_t _sample_perf
 
perf_counter_t _measure_perf
 
perf_counter_t _comms_errors
 
calibration_s_cal {nullptr}
 
bool _collect_phase {false}
 

Detailed Description

Definition at line 309 of file bmp388.h.

Constructor & Destructor Documentation

◆ BMP388()

BMP388::BMP388 ( IBMP388 interface)

Definition at line 45 of file bmp388.cpp.

References _px4_baro, DRV_DEVTYPE_BMP388, and PX4Barometer::set_device_type().

Here is the call graph for this function:

◆ ~BMP388()

BMP388::~BMP388 ( )
virtual

Definition at line 56 of file bmp388.cpp.

References _comms_errors, _interface, _measure_perf, _sample_perf, perf_free(), and stop().

Here is the call graph for this function:

Member Function Documentation

◆ collect()

int BMP388::collect ( )
private

Definition at line 180 of file bmp388.cpp.

References _collect_phase, _comms_errors, _px4_baro, _sample_perf, BMP3_PRESS, BMP3_TEMP, data, get_sensor_data(), hrt_absolute_time(), hrt_abstime, OK, perf_begin(), perf_cancel(), perf_count(), perf_end(), perf_event_count(), PX4Barometer::set_error_count(), PX4Barometer::set_temperature(), and PX4Barometer::update().

Referenced by init(), and Run().

Here is the call graph for this function:
Here is the caller graph for this function:

◆ compensate_data()

bool BMP388::compensate_data ( uint8_t  sensor_comp,
const struct bmp3_uncomp_data uncomp_data,
struct bmp3_data comp_data 
)
private

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

Definition at line 571 of file bmp388.cpp.

References _cal, BMP3_PRESS, BMP3_TEMP, compensate_pressure(), compensate_temperature(), OK, bmp3_data::pressure, bmp3_calib_data::reg_calib_data, and bmp3_data::temperature.

Referenced by get_sensor_data().

Here is the call graph for this function:
Here is the caller graph for this function:

◆ get_calib_data()

bool BMP388::get_calib_data ( )
private

◆ get_measurement_time()

uint32_t BMP388::get_measurement_time ( uint8_t  osr_t,
uint8_t  osr_p 
)
private

Definition at line 302 of file bmp388.cpp.

References BMP3_NO_OVERSAMPLING, BMP3_OVERSAMPLING_16X, BMP3_OVERSAMPLING_2X, BMP3_OVERSAMPLING_32X, BMP3_OVERSAMPLING_4X, and BMP3_OVERSAMPLING_8X.

Referenced by set_sensor_settings().

Here is the caller graph for this function:

◆ get_sensor_data()

bool BMP388::get_sensor_data ( uint8_t  sensor_comp,
struct bmp3_data comp_data 
)
private

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.

Definition at line 602 of file bmp388.cpp.

References _interface, BMP3_DATA_ADDR, BMP3_P_T_DATA_LEN, compensate_data(), IBMP388::get_reg_buf(), OK, and parse_sensor_data().

Referenced by collect().

Here is the call graph for this function:
Here is the caller graph for this function:

◆ init()

int BMP388::init ( )
virtual

Definition at line 70 of file bmp388.cpp.

References _cal, _interface, _measure_interval, BMP3_CALIB_DATA_ADDR, BMP3_CHIP_ID, BMP3_CHIP_ID_ADDR, collect(), IBMP388::get_calibration(), IBMP388::get_reg(), measure(), OK, set_sensor_settings(), soft_reset(), start(), and validate_trimming_param().

Referenced by bmp388::start_bus().

Here is the call graph for this function:
Here is the caller graph for this function:

◆ measure()

int BMP388::measure ( )
private

Definition at line 160 of file bmp388.cpp.

References _collect_phase, _comms_errors, _measure_perf, BMP3_FORCED_MODE, OK, perf_begin(), perf_cancel(), perf_count(), perf_end(), and set_op_mode().

Referenced by init(), and Run().

Here is the call graph for this function:
Here is the caller graph for this function:

◆ print_info()

void BMP388::print_info ( )

Definition at line 119 of file bmp388.cpp.

References _comms_errors, _measure_interval, _measure_perf, _px4_baro, _sample_perf, perf_print_counter(), and PX4Barometer::print_status().

Referenced by bmp388::status().

Here is the call graph for this function:
Here is the caller graph for this function:

◆ Run()

void BMP388::Run ( )
overrideprivate

Definition at line 150 of file bmp388.cpp.

References _collect_phase, collect(), and measure().

Here is the call graph for this function:

◆ set_op_mode()

bool BMP388::set_op_mode ( uint8_t  op_mode)
private

This API sets the power mode of the sensor.

Refer: https://github.com/BoschSensortec/BMP3-Sensor-API/blob/master/bmp3.c

Definition at line 424 of file bmp388.cpp.

References _interface, BMP3_GET_BITS, BMP3_OP_MODE_MSK, BMP3_POST_SLEEP_WAIT_TIME, BMP3_PWR_CTRL_ADDR, BMP3_SET_BITS, BMP3_SLEEP_MODE, IBMP388::get_reg(), OK, and IBMP388::set_reg().

Referenced by measure().

Here is the call graph for this function:
Here is the caller graph for this function:

◆ set_sensor_settings()

bool BMP388::set_sensor_settings ( )
private

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

Definition at line 361 of file bmp388.cpp.

References _iir_coef, _interface, _measure_interval, _odr, _osr_p, _osr_t, BMP3_ENABLE, BMP3_IIR_ADDR, BMP3_ODR_ADDR, BMP3_OSR_ADDR, BMP3_PWR_CTRL_ADDR, BMP3_SET_BITS, BMP3_SET_BITS_POS_0, get_measurement_time(), OK, and IBMP388::set_reg().

Referenced by init().

Here is the call graph for this function:
Here is the caller graph for this function:

◆ soft_reset()

bool BMP388::soft_reset ( )
private

This API performs the soft reset of the sensor.

Refer: https://github.com/BoschSensortec/BMP3-Sensor-API/blob/master/bmp3.c

Definition at line 219 of file bmp388.cpp.

References _interface, BMP3_CMD_ADDR, BMP3_CMD_ERR, BMP3_CMD_RDY, BMP3_ERR_REG_ADDR, BMP3_POST_RESET_WAIT_TIME, BMP3_SENS_STATUS_REG_ADDR, BPM3_CMD_SOFT_RESET, IBMP388::get_reg(), OK, IBMP388::set_reg(), and status.

Referenced by init().

Here is the call graph for this function:
Here is the caller graph for this function:

◆ start()

void BMP388::start ( )
private

Definition at line 130 of file bmp388.cpp.

References _collect_phase, _measure_interval, and stop().

Referenced by init().

Here is the call graph for this function:
Here is the caller graph for this function:

◆ stop()

void BMP388::stop ( )
private

Definition at line 141 of file bmp388.cpp.

Referenced by start(), and ~BMP388().

Here is the caller graph for this function:

◆ validate_trimming_param()

bool BMP388::validate_trimming_param ( )
private

Definition at line 276 of file bmp388.cpp.

References _cal, _interface, BMP3_CALIB_DATA_LEN, BMP3_TRIM_CRC_DATA_ADDR, cal_crc(), and IBMP388::get_reg().

Referenced by init().

Here is the call graph for this function:
Here is the caller graph for this function:

Member Data Documentation

◆ _cal

calibration_s* BMP388::_cal {nullptr}
private

Definition at line 333 of file bmp388.h.

Referenced by compensate_data(), init(), and validate_trimming_param().

◆ _collect_phase

bool BMP388::_collect_phase {false}
private

Definition at line 335 of file bmp388.h.

Referenced by collect(), measure(), Run(), and start().

◆ _comms_errors

perf_counter_t BMP388::_comms_errors
private

Definition at line 331 of file bmp388.h.

Referenced by collect(), measure(), print_info(), and ~BMP388().

◆ _iir_coef

uint8_t BMP388::_iir_coef {BMP3_IIR_FILTER_DISABLE}
private

Definition at line 327 of file bmp388.h.

Referenced by set_sensor_settings().

◆ _interface

IBMP388* BMP388::_interface {nullptr}
private

◆ _measure_interval

unsigned BMP388::_measure_interval {0}
private

Definition at line 323 of file bmp388.h.

Referenced by init(), print_info(), set_sensor_settings(), and start().

◆ _measure_perf

perf_counter_t BMP388::_measure_perf
private

Definition at line 330 of file bmp388.h.

Referenced by measure(), print_info(), and ~BMP388().

◆ _odr

uint8_t BMP388::_odr {BMP3_ODR_50_HZ}
private

Definition at line 326 of file bmp388.h.

Referenced by set_sensor_settings().

◆ _osr_p

uint8_t BMP388::_osr_p {BMP3_OVERSAMPLING_16X}
private

Definition at line 325 of file bmp388.h.

Referenced by set_sensor_settings().

◆ _osr_t

uint8_t BMP388::_osr_t {BMP3_OVERSAMPLING_2X}
private

Definition at line 324 of file bmp388.h.

Referenced by set_sensor_settings().

◆ _px4_baro

PX4Barometer BMP388::_px4_baro
private

Definition at line 320 of file bmp388.h.

Referenced by BMP388(), collect(), and print_info().

◆ _sample_perf

perf_counter_t BMP388::_sample_perf
private

Definition at line 329 of file bmp388.h.

Referenced by collect(), print_info(), and ~BMP388().


The documentation for this class was generated from the following files: