Improve default baro determination for backward compatibility
This commit is contained in:
parent
2c135547e5
commit
e4b067ed60
|
@ -58,41 +58,60 @@ void pgResetFn_barometerConfig(barometerConfig_t *barometerConfig)
|
|||
barometerConfig->baro_hardware = BARO_DEFAULT;
|
||||
|
||||
// For backward compatibility; ceate a valid default value for bus parameters
|
||||
//
|
||||
// 1. If DEFAULT_BARO_xxx is defined, use it.
|
||||
// 2. Determine default based on USE_BARO_xxx
|
||||
// a. Precedence is in the order of popularity; BMP280, MS5611 then BMP085, then
|
||||
// b. If SPI variant is specified, it is likely onboard, so take it.
|
||||
|
||||
#ifdef USE_BARO_BMP085
|
||||
barometerConfig->baro_bustype = BUSTYPE_I2C;
|
||||
barometerConfig->baro_i2c_device = I2C_DEV_TO_CFG(BARO_I2C_INSTANCE);
|
||||
barometerConfig->baro_i2c_address = BMP085_I2C_ADDR;
|
||||
barometerConfig->baro_spi_device = SPI_DEV_TO_CFG(SPIINVALID);
|
||||
barometerConfig->baro_spi_csn = IO_TAG_NONE;
|
||||
#if !(defined(DEFAULT_BARO_SPI_BMP280) || defined(DEFAULT_BARO_BMP280) || defined(DEFAULT_BARO_SPI_MS5611) || defined(DEFAULT_BARO_BARO_MS5611) || defined(DEFAULT_BARO_BMP085))
|
||||
#if defined(USE_BARO_BMP280) || defined(USE_BARO_SPI_BMP280)
|
||||
#if defined(USE_BARO_SPI_BMP280)
|
||||
#define DEFAULT_BARO_SPI_BMP280
|
||||
#else
|
||||
#define DEFAULT_BARO_BMP280
|
||||
#endif
|
||||
#elif defined(USE_BARO_MS5611) || defined(USE_BARO_SPI_MS5611)
|
||||
#if defined(USE_BARO_SPI_MS5611)
|
||||
barometerConfig->baro_bustype = BUSTYPE_SPI;
|
||||
barometerConfig->baro_spi_device = SPI_DEV_TO_CFG(spiDeviceByInstance(MS5611_SPI_INSTANCE));
|
||||
barometerConfig->baro_spi_csn = IO_TAG(MS5611_CS_PIN);
|
||||
barometerConfig->baro_i2c_device = I2C_DEV_TO_CFG(I2CINVALID);
|
||||
barometerConfig->baro_i2c_address = 0;
|
||||
#define DEFAULT_BARO_SPI_MS5611
|
||||
#else
|
||||
barometerConfig->baro_bustype = BUSTYPE_I2C;
|
||||
barometerConfig->baro_i2c_device = I2C_DEV_TO_CFG(BARO_I2C_INSTANCE);
|
||||
barometerConfig->baro_i2c_address = MS5611_I2C_ADDR;
|
||||
barometerConfig->baro_spi_device = SPI_DEV_TO_CFG(SPIINVALID);
|
||||
barometerConfig->baro_spi_csn = IO_TAG_NONE;
|
||||
#define DEFAULT_BARO_MS5611
|
||||
#endif
|
||||
#elif defined(USE_BARO_BMP280) || defined(USE_BARO_SPI_BMP280)
|
||||
#if defined(USE_BARO_SPI_BMP280)
|
||||
#elif defined(DEFAULT_BARO_BMP085)
|
||||
#define DEFAULT_BARO_BMP085
|
||||
#endif
|
||||
#endif
|
||||
|
||||
#if defined(DEFAULT_BARO_SPI_BMP280)
|
||||
barometerConfig->baro_bustype = BUSTYPE_SPI;
|
||||
barometerConfig->baro_spi_device = SPI_DEV_TO_CFG(spiDeviceByInstance(BMP280_SPI_INSTANCE));
|
||||
barometerConfig->baro_spi_csn = IO_TAG(BMP280_CS_PIN);
|
||||
barometerConfig->baro_i2c_device = I2C_DEV_TO_CFG(I2CINVALID);
|
||||
barometerConfig->baro_i2c_address = 0;
|
||||
#else
|
||||
#elif defined(DEFAULT_BARO_BMP280)
|
||||
barometerConfig->baro_bustype = BUSTYPE_I2C;
|
||||
barometerConfig->baro_i2c_device = I2C_DEV_TO_CFG(BARO_I2C_INSTANCE);
|
||||
barometerConfig->baro_i2c_address = BMP280_I2C_ADDR;
|
||||
barometerConfig->baro_spi_device = SPI_DEV_TO_CFG(SPIINVALID);
|
||||
barometerConfig->baro_spi_csn = IO_TAG_NONE;
|
||||
#endif
|
||||
#elif defined(DEFAULT_BARO_SPI_MS5611)
|
||||
barometerConfig->baro_bustype = BUSTYPE_SPI;
|
||||
barometerConfig->baro_spi_device = SPI_DEV_TO_CFG(spiDeviceByInstance(MS5611_SPI_INSTANCE));
|
||||
barometerConfig->baro_spi_csn = IO_TAG(MS5611_CS_PIN);
|
||||
barometerConfig->baro_i2c_device = I2C_DEV_TO_CFG(I2CINVALID);
|
||||
barometerConfig->baro_i2c_address = 0;
|
||||
#elif defined(DEFAULT_BARO_BARO_MS5611)
|
||||
barometerConfig->baro_bustype = BUSTYPE_I2C;
|
||||
barometerConfig->baro_i2c_device = I2C_DEV_TO_CFG(BARO_I2C_INSTANCE);
|
||||
barometerConfig->baro_i2c_address = MS5611_I2C_ADDR;
|
||||
barometerConfig->baro_spi_device = SPI_DEV_TO_CFG(SPIINVALID);
|
||||
barometerConfig->baro_spi_csn = IO_TAG_NONE;
|
||||
#elif defined(DEFAULT_BARO_BMP085)
|
||||
barometerConfig->baro_bustype = BUSTYPE_I2C;
|
||||
barometerConfig->baro_i2c_device = I2C_DEV_TO_CFG(BARO_I2C_INSTANCE);
|
||||
barometerConfig->baro_i2c_address = BMP085_I2C_ADDR;
|
||||
barometerConfig->baro_spi_device = SPI_DEV_TO_CFG(SPIINVALID);
|
||||
barometerConfig->baro_spi_csn = IO_TAG_NONE;
|
||||
#else
|
||||
barometerConfig->baro_hardware = BARO_NONE;
|
||||
barometerConfig->baro_bustype = BUSTYPE_NONE;
|
||||
|
|
|
@ -74,7 +74,6 @@
|
|||
#undef USE_DASHBOARD
|
||||
#undef USE_I2C_OLED_DISPLAY
|
||||
|
||||
#if 0
|
||||
// Support for iFlight OMNIBUS F4 V3
|
||||
// Has ICM20608 instead of MPU6000
|
||||
// OMNIBUSF4SD is linked with both MPU6000 and MPU6500 drivers
|
||||
|
@ -86,7 +85,6 @@
|
|||
#define GYRO_MPU6500_ALIGN GYRO_MPU6000_ALIGN
|
||||
#define ACC_MPU6500_ALIGN ACC_MPU6000_ALIGN
|
||||
#endif
|
||||
#endif
|
||||
|
||||
#define MAG
|
||||
#define USE_MAG_HMC5883
|
||||
|
@ -104,7 +102,13 @@
|
|||
#endif
|
||||
#define USE_BARO_BMP280
|
||||
#define USE_BARO_MS5611
|
||||
#define BARO_I2C_INSTANCE (I2CDEV_2)
|
||||
#define BARO_I2C_INSTANCE (I2CDEV_2)
|
||||
|
||||
#if defined(OMNIBUSF4SD)
|
||||
#define DEFAULT_BARO_SPI_BMP280
|
||||
#else
|
||||
#define DEFAULT_BARO_BMP280
|
||||
#endif
|
||||
|
||||
#define OSD
|
||||
#define USE_MAX7456
|
||||
|
@ -193,15 +197,14 @@
|
|||
|
||||
#define USE_I2C
|
||||
#define USE_I2C_DEVICE_2
|
||||
#define I2C2_SCL PB10 // PB10, shared with UART3TX
|
||||
#define I2C2_SDA PB11 // PB11, shared with UART3RX
|
||||
#define I2C2_SCL NONE // PB10, shared with UART3TX
|
||||
#define I2C2_SDA NONE // PB11, shared with UART3RX
|
||||
#if defined(OMNIBUSF4) || defined(OMNIBUSF4SD)
|
||||
#define USE_I2C_DEVICE_3
|
||||
#define I2C3_SCL NONE // PA8, PWM6
|
||||
#define I2C3_SDA NONE // PC9, CH6
|
||||
#endif
|
||||
#define I2C_DEVICE (I2CDEV_2)
|
||||
#define OLED_I2C_INSTANCE (I2CDEV_2)
|
||||
|
||||
#define USE_ADC
|
||||
#define CURRENT_METER_ADC_PIN PC1 // Direct from CRNT pad (part of onboard sensor for Pro)
|
||||
|
|
Loading…
Reference in New Issue