mirror of
https://github.com/betaflight/betaflight.git
synced 2025-07-14 03:50:02 +03:00
Ammend BMP085 driver for configurability of EOC and XCLR pin
This commit is contained in:
parent
eea9242d7b
commit
b749d56d9e
10 changed files with 70 additions and 76 deletions
|
@ -4577,6 +4577,8 @@ const cliResourceValue_t resourceTable[] = {
|
|||
#endif
|
||||
#ifdef USE_BARO
|
||||
DEFS( OWNER_BARO_CS, PG_BAROMETER_CONFIG, barometerConfig_t, baro_spi_csn ),
|
||||
DEFS( OWNER_BARO_EOC, PG_BAROMETER_CONFIG, barometerConfig_t, baro_eoc_tag ),
|
||||
DEFS( OWNER_BARO_XCLR, PG_BAROMETER_CONFIG, barometerConfig_t, baro_xclr_tag ),
|
||||
#endif
|
||||
#ifdef USE_MAG
|
||||
DEFS( OWNER_COMPASS_CS, PG_COMPASS_CONFIG, compassConfig_t, mag_spi_csn ),
|
||||
|
|
|
@ -39,21 +39,19 @@
|
|||
|
||||
#ifdef USE_BARO
|
||||
|
||||
#if defined(BARO_EOC_PIN)
|
||||
|
||||
static IO_t eocIO;
|
||||
|
||||
static bool isConversionComplete = false;
|
||||
static bool isEOCConnected = true;
|
||||
static bool isEOCConnected = false;
|
||||
|
||||
// EXTI14 for BMP085 End of Conversion Interrupt
|
||||
void bmp085_extiHandler(extiCallbackRec_t* cb)
|
||||
#ifdef USE_EXTI
|
||||
static IO_t eocIO;
|
||||
static extiCallbackRec_t exti;
|
||||
|
||||
static void bmp085_extiHandler(extiCallbackRec_t* cb)
|
||||
{
|
||||
UNUSED(cb);
|
||||
isConversionComplete = true;
|
||||
}
|
||||
|
||||
# endif
|
||||
#endif
|
||||
|
||||
typedef struct {
|
||||
int16_t ac1;
|
||||
|
@ -131,30 +129,17 @@ static int32_t bmp085_get_temperature(uint32_t ut);
|
|||
static int32_t bmp085_get_pressure(uint32_t up);
|
||||
STATIC_UNIT_TESTED void bmp085_calculate(int32_t *pressure, int32_t *temperature);
|
||||
|
||||
static IO_t xclrIO;
|
||||
static bool bmp085TestEOCConnected(baroDev_t *baro, const bmp085Config_t *config);
|
||||
|
||||
#ifdef BARO_XCLR_PIN
|
||||
static IO_t xclrIO = IO_NONE;
|
||||
#define BMP085_OFF IOLo(xclrIO);
|
||||
#define BMP085_ON IOHi(xclrIO);
|
||||
#else
|
||||
#define BMP085_OFF
|
||||
#define BMP085_ON
|
||||
#endif
|
||||
|
||||
|
||||
void bmp085InitXclrIO(const bmp085Config_t *config)
|
||||
static void bmp085InitXclrIO(const bmp085Config_t *config)
|
||||
{
|
||||
if (!xclrIO && config && config->xclrIO) {
|
||||
xclrIO = IOGetByTag(config->xclrIO);
|
||||
IOInit(xclrIO, OWNER_BARO_CS, 0);
|
||||
IOConfigGPIO(xclrIO, IOCFG_OUT_PP);
|
||||
}
|
||||
}
|
||||
|
||||
void bmp085Disable(const bmp085Config_t *config)
|
||||
{
|
||||
bmp085InitXclrIO(config);
|
||||
BMP085_OFF;
|
||||
xclrIO = IOGetByTag(config->xclrTag);
|
||||
IOInit(xclrIO, OWNER_BARO_XCLR, 0);
|
||||
IOConfigGPIO(xclrIO, IOCFG_OUT_PP);
|
||||
}
|
||||
|
||||
bool bmp085Detect(const bmp085Config_t *config, baroDev_t *baro)
|
||||
|
@ -163,25 +148,20 @@ bool bmp085Detect(const bmp085Config_t *config, baroDev_t *baro)
|
|||
bool ack;
|
||||
bool defaultAddressApplied = false;
|
||||
|
||||
#if defined(BARO_EOC_PIN)
|
||||
IO_t eocIO = IO_NONE;
|
||||
#endif
|
||||
|
||||
if (bmp085InitDone)
|
||||
return true;
|
||||
|
||||
bmp085InitXclrIO(config);
|
||||
BMP085_ON; // enable baro
|
||||
|
||||
#if defined(BARO_EOC_PIN) && defined(USE_EXTI)
|
||||
if (config && config->eocIO) {
|
||||
eocIO = IOGetByTag(config->eocIO);
|
||||
// EXTI interrupt for barometer EOC
|
||||
IOInit(eocIO, OWNER_BARO_EXTI, 0);
|
||||
EXTIHandlerInit(&baro->exti, bmp085_extiHandler);
|
||||
EXTIConfig(eocIO, &baro->exti, NVIC_PRIO_BARO_EXTI, IOCFG_IN_FLOATING, EXTI_TRIGGER_RISING);
|
||||
EXTIEnable(eocIO, true);
|
||||
}
|
||||
#ifdef USE_EXTI
|
||||
// EXTI interrupt for barometer EOC
|
||||
|
||||
eocIO = IOGetByTag(config->eocTag);
|
||||
IOInit(eocIO, OWNER_BARO_EOC, 0);
|
||||
EXTIHandlerInit(&exti, bmp085_extiHandler);
|
||||
EXTIConfig(eocIO, &exti, NVIC_PRIO_BARO_EXTI, IOCFG_IN_FLOATING, EXTI_TRIGGER_RISING);
|
||||
EXTIEnable(eocIO, true);
|
||||
#else
|
||||
UNUSED(config);
|
||||
#endif
|
||||
|
@ -213,17 +193,19 @@ bool bmp085Detect(const bmp085Config_t *config, baroDev_t *baro)
|
|||
baro->start_up = bmp085_start_up;
|
||||
baro->get_up = bmp085_get_up;
|
||||
baro->calculate = bmp085_calculate;
|
||||
#if defined(BARO_EOC_PIN)
|
||||
|
||||
isEOCConnected = bmp085TestEOCConnected(baro, config);
|
||||
#endif
|
||||
|
||||
bmp085InitDone = true;
|
||||
return true;
|
||||
}
|
||||
}
|
||||
|
||||
#if defined(BARO_EOC_PIN)
|
||||
if (eocIO)
|
||||
#ifdef USE_EXTI
|
||||
if (eocIO) {
|
||||
IORelease(eocIO);
|
||||
EXTIRelease(eocIO);
|
||||
}
|
||||
#endif
|
||||
|
||||
BMP085_OFF;
|
||||
|
@ -290,9 +272,8 @@ static int32_t bmp085_get_pressure(uint32_t up)
|
|||
|
||||
static void bmp085_start_ut(baroDev_t *baro)
|
||||
{
|
||||
#if defined(BARO_EOC_PIN)
|
||||
isConversionComplete = false;
|
||||
#endif
|
||||
|
||||
busWriteRegister(&baro->busdev, BMP085_CTRL_MEAS_REG, BMP085_T_MEASURE);
|
||||
}
|
||||
|
||||
|
@ -300,12 +281,10 @@ static void bmp085_get_ut(baroDev_t *baro)
|
|||
{
|
||||
uint8_t data[2];
|
||||
|
||||
#if defined(BARO_EOC_PIN)
|
||||
// return old baro value if conversion time exceeds datasheet max when EOC is connected
|
||||
if ((isEOCConnected) && (!isConversionComplete)) {
|
||||
return;
|
||||
}
|
||||
#endif
|
||||
|
||||
busReadRegisterBuffer(&baro->busdev, BMP085_ADC_OUT_MSB_REG, data, 2);
|
||||
bmp085_ut = (data[0] << 8) | data[1];
|
||||
|
@ -317,9 +296,7 @@ static void bmp085_start_up(baroDev_t *baro)
|
|||
|
||||
ctrl_reg_data = BMP085_P_MEASURE + (bmp085.oversampling_setting << 6);
|
||||
|
||||
#if defined(BARO_EOC_PIN)
|
||||
isConversionComplete = false;
|
||||
#endif
|
||||
|
||||
busWriteRegister(&baro->busdev, BMP085_CTRL_MEAS_REG, ctrl_reg_data);
|
||||
}
|
||||
|
@ -332,12 +309,10 @@ static void bmp085_get_up(baroDev_t *baro)
|
|||
{
|
||||
uint8_t data[3];
|
||||
|
||||
#if defined(BARO_EOC_PIN)
|
||||
// return old baro value if conversion time exceeds datasheet max when EOC is connected
|
||||
if ((isEOCConnected) && (!isConversionComplete)) {
|
||||
return;
|
||||
}
|
||||
#endif
|
||||
|
||||
busReadRegisterBuffer(&baro->busdev, BMP085_ADC_OUT_MSB_REG, data, 3);
|
||||
bmp085_up = (((uint32_t) data[0] << 16) | ((uint32_t) data[1] << 8) | (uint32_t) data[2])
|
||||
|
@ -379,12 +354,17 @@ static void bmp085_get_cal_param(busDevice_t *busdev)
|
|||
bmp085.cal_param.md = (data[20] << 8) | data[21];
|
||||
}
|
||||
|
||||
#if defined(BARO_EOC_PIN)
|
||||
bool bmp085TestEOCConnected(baroDev_t *baro, const bmp085Config_t *config)
|
||||
static bool bmp085TestEOCConnected(baroDev_t *baro, const bmp085Config_t *config)
|
||||
{
|
||||
UNUSED(config);
|
||||
|
||||
#ifdef USE_EXTI
|
||||
if (!bmp085InitDone && eocIO) {
|
||||
// EOC should be low at this point. If not, assume EOC is not working
|
||||
if (IORead(eocIO)) {
|
||||
return false;
|
||||
}
|
||||
|
||||
bmp085_start_ut(baro);
|
||||
delayMicroseconds(UT_DELAY * 2); // wait twice as long as normal, just to be sure
|
||||
|
||||
|
@ -394,8 +374,11 @@ bool bmp085TestEOCConnected(baroDev_t *baro, const bmp085Config_t *config)
|
|||
return true;
|
||||
}
|
||||
}
|
||||
return false; // assume EOC is not connected
|
||||
}
|
||||
#else
|
||||
UNUSED(baro);
|
||||
#endif
|
||||
|
||||
return false; // assume EOC is not connected
|
||||
}
|
||||
|
||||
#endif /* BARO */
|
||||
|
|
|
@ -25,16 +25,11 @@
|
|||
#define BMP085_I2C_ADDR 0x77
|
||||
|
||||
typedef struct bmp085Config_s {
|
||||
ioTag_t xclrIO;
|
||||
ioTag_t eocIO;
|
||||
ioTag_t xclrTag;
|
||||
ioTag_t eocTag;
|
||||
} bmp085Config_t;
|
||||
|
||||
bool bmp085Detect(const bmp085Config_t *config, baroDev_t *baro);
|
||||
void bmp085Disable(const bmp085Config_t *config);
|
||||
|
||||
#if defined(BARO_EOC_PIN)
|
||||
bool bmp085TestEOCConnected(baroDev_t *baro, const bmp085Config_t *config);
|
||||
#endif
|
||||
|
||||
#ifdef UNIT_TEST
|
||||
void RCC_APB2PeriphClockCmd(uint32_t RCC_APB2Periph, FunctionalState NewState);
|
||||
|
|
|
@ -54,6 +54,8 @@ typedef struct bmp280_calib_param_s {
|
|||
int16_t dig_P9; /* calibration P9 data */
|
||||
} __attribute__((packed)) bmp280_calib_param_t; // packed as we read directly from the device into this structure.
|
||||
|
||||
STATIC_ASSERT(sizeof(bmp280_calib_param_t) == BMP280_PRESSURE_TEMPERATURE_CALIB_DATA_LENGTH, bmp280_calibration_structure_incorrectly_packed);
|
||||
|
||||
STATIC_UNIT_TESTED int32_t t_fine; /* calibration t_fine data */
|
||||
|
||||
static uint8_t bmp280_chip_id = 0;
|
||||
|
@ -71,8 +73,6 @@ STATIC_UNIT_TESTED void bmp280_calculate(int32_t *pressure, int32_t *temperature
|
|||
|
||||
void bmp280BusInit(busDevice_t *busdev)
|
||||
{
|
||||
STATIC_ASSERT(sizeof(bmp280_calib_param_t) == BMP280_PRESSURE_TEMPERATURE_CALIB_DATA_LENGTH, bmp280_calibration_structure_incorrectly_packed);
|
||||
|
||||
#ifdef USE_BARO_SPI_BMP280
|
||||
if (busdev->bustype == BUSTYPE_SPI) {
|
||||
IOHi(busdev->busdev_u.spi.csnPin); // Disable
|
||||
|
|
|
@ -56,7 +56,7 @@ const char * const ownerNames[OWNER_TOTAL_COUNT] = {
|
|||
"RX_SPI_CS",
|
||||
"SPI_CS",
|
||||
"GYRO_EXTI",
|
||||
"BARO_EXTI",
|
||||
"BARO_EOC",
|
||||
"COMPASS_EXTI",
|
||||
"USB",
|
||||
"USB_DETECT",
|
||||
|
@ -98,4 +98,5 @@ const char * const ownerNames[OWNER_TOTAL_COUNT] = {
|
|||
"QSPI_BK2IO2",
|
||||
"QSPI_BK2IO3",
|
||||
"QSPI_BK2CS",
|
||||
"BARO_XCLR",
|
||||
};
|
||||
|
|
|
@ -54,7 +54,7 @@ typedef enum {
|
|||
OWNER_RX_SPI_CS,
|
||||
OWNER_SPI_CS,
|
||||
OWNER_GYRO_EXTI,
|
||||
OWNER_BARO_EXTI,
|
||||
OWNER_BARO_EOC,
|
||||
OWNER_COMPASS_EXTI,
|
||||
OWNER_USB,
|
||||
OWNER_USB_DETECT,
|
||||
|
@ -96,6 +96,7 @@ typedef enum {
|
|||
OWNER_QUADSPI_BK2IO2,
|
||||
OWNER_QUADSPI_BK2IO3,
|
||||
OWNER_QUADSPI_BK2CS,
|
||||
OWNER_BARO_XCLR,
|
||||
OWNER_TOTAL_COUNT
|
||||
} resourceOwner_e;
|
||||
|
||||
|
|
|
@ -119,6 +119,9 @@ void pgResetFn_barometerConfig(barometerConfig_t *barometerConfig)
|
|||
barometerConfig->baro_spi_device = SPI_DEV_TO_CFG(SPIINVALID);
|
||||
barometerConfig->baro_spi_csn = IO_TAG_NONE;
|
||||
#endif
|
||||
|
||||
barometerConfig->baro_eoc_tag = IO_TAG(BARO_EOC_PIN);
|
||||
barometerConfig->baro_xclr_tag = IO_TAG(BARO_XCLR_PIN);
|
||||
}
|
||||
|
||||
static uint16_t calibratingB = 0; // baro calibration = get new ground pressure value
|
||||
|
@ -183,15 +186,11 @@ bool baroDetect(baroDev_t *dev, baroSensor_e baroHardwareToUse)
|
|||
case BARO_BMP085:
|
||||
#ifdef USE_BARO_BMP085
|
||||
{
|
||||
const bmp085Config_t *bmp085Config = NULL;
|
||||
static bmp085Config_t defaultBMP085Config;
|
||||
defaultBMP085Config.xclrTag = barometerConfig()->baro_xclr_tag;
|
||||
defaultBMP085Config.eocTag = barometerConfig()->baro_eoc_tag;
|
||||
|
||||
#if defined(BARO_XCLR_PIN) && defined(BARO_EOC_PIN)
|
||||
static const bmp085Config_t defaultBMP085Config = {
|
||||
.xclrIO = IO_TAG(BARO_XCLR_PIN),
|
||||
.eocIO = IO_TAG(BARO_EOC_PIN),
|
||||
};
|
||||
bmp085Config = &defaultBMP085Config;
|
||||
#endif
|
||||
static const bmp085Config_t *bmp085Config = &defaultBMP085Config;
|
||||
|
||||
if (bmp085Detect(bmp085Config, dev)) {
|
||||
baroHardware = BARO_BMP085;
|
||||
|
|
|
@ -45,6 +45,8 @@ typedef struct barometerConfig_s {
|
|||
uint8_t baro_sample_count; // size of baro filter array
|
||||
uint16_t baro_noise_lpf; // additional LPF to reduce baro noise
|
||||
uint16_t baro_cf_vel; // apply Complimentary Filter to keep the calculated velocity based on baro velocity (i.e. near real velocity)
|
||||
ioTag_t baro_eoc_tag;
|
||||
ioTag_t baro_xclr_tag;
|
||||
} barometerConfig_t;
|
||||
|
||||
PG_DECLARE(barometerConfig_t, barometerConfig);
|
||||
|
|
|
@ -447,6 +447,12 @@
|
|||
#ifndef BARO_I2C_INSTANCE
|
||||
#define BARO_I2C_INSTANCE I2C_DEVICE
|
||||
#endif
|
||||
#ifndef BARO_EOC_PIN
|
||||
#define BARO_EOC_PIN NONE
|
||||
#endif
|
||||
#ifndef BARO_XCLR_PIN
|
||||
#define BARO_XCLR_PIN NONE
|
||||
#endif
|
||||
#endif
|
||||
|
||||
#ifdef USE_ADC
|
||||
|
|
|
@ -64,6 +64,11 @@
|
|||
#undef USE_VARIO
|
||||
#endif
|
||||
|
||||
#if defined(USE_BARO) && !defined(BARO_EOC_PIN)
|
||||
#define BARO_EOC_PIN NONE
|
||||
#endif
|
||||
|
||||
|
||||
#if !defined(USE_SERIAL_RX)
|
||||
#undef USE_SERIALRX_CRSF
|
||||
#undef USE_SERIALRX_IBUS
|
||||
|
|
Loading…
Add table
Add a link
Reference in a new issue