diff --git a/src/main/drivers/barometer_bmp085.c b/src/main/drivers/barometer_bmp085.c index 663d6741f..6fd107aae 100755 --- a/src/main/drivers/barometer_bmp085.c +++ b/src/main/drivers/barometer_bmp085.c @@ -116,6 +116,25 @@ static int32_t bmp085_get_temperature(uint32_t ut); static int32_t bmp085_get_pressure(uint32_t up); static void bmp085_calculate(int32_t *pressure, int32_t *temperature); +#define BMP085_OFF digitalLo(BARO_GPIO, BARO_PIN); +#define BMP085_ON digitalHi(BARO_GPIO, BARO_PIN); + +void bmp085Disable(void) +{ + + if (hse_value != 12000000) { + RCC_APB2PeriphClockCmd(RCC_APB2Periph_GPIOC, ENABLE); + + // PC13 (BMP085's XCLR reset input, which we use to disable it). Only needed when running at 8MHz + gpio_config_t gpio; + gpio.pin = Pin_13; + gpio.speed = Speed_2MHz; + gpio.mode = Mode_Out_PP; + gpioInit(GPIOC, &gpio); + } + BMP085_OFF; +} + bool bmp085Detect(baro_t *baro) { uint8_t data; diff --git a/src/main/drivers/barometer_bmp085.h b/src/main/drivers/barometer_bmp085.h index 949494fce..31f0223ea 100755 --- a/src/main/drivers/barometer_bmp085.h +++ b/src/main/drivers/barometer_bmp085.h @@ -18,3 +18,4 @@ #pragma once bool bmp085Detect(baro_t *baro); +void bmp085Disable(void); diff --git a/src/main/drivers/barometer_ms5611.c b/src/main/drivers/barometer_ms5611.c index 9723cef57..7604fc6fd 100644 --- a/src/main/drivers/barometer_ms5611.c +++ b/src/main/drivers/barometer_ms5611.c @@ -28,9 +28,6 @@ // MS5611, Standard address 0x77 #define MS5611_ADDR 0x77 -// Autodetect: turn off BMP085 while initializing ms5611 and check PROM crc to confirm device -#define BMP085_OFF digitalLo(BARO_GPIO, BARO_PIN); -#define BMP085_ON digitalHi(BARO_GPIO, BARO_PIN); #define CMD_RESET 0x1E // ADC reset command #define CMD_ADC_READ 0x00 // ADC read command @@ -66,22 +63,8 @@ bool ms5611Detect(baro_t *baro) uint8_t sig; int i; - if (hse_value != 12000000) { - RCC_APB2PeriphClockCmd(RCC_APB2Periph_GPIOC, ENABLE); - - // PC13 (BMP085's XCLR reset input, which we use to disable it). Only needed when running at 8MHz - gpio_config_t gpio; - gpio.pin = Pin_13; - gpio.speed = Speed_2MHz; - gpio.mode = Mode_Out_PP; - gpioInit(GPIOC, &gpio); - BMP085_OFF; - } - delay(10); // No idea how long the chip takes to power-up, but let's make it 10ms - // BMP085 is disabled. If we have a MS5611, it will reply. if no reply, means either - // we have BMP085 or no baro at all. ack = i2cRead(MS5611_ADDR, CMD_PROM_RD, 1, &sig); if (!ack) return false; diff --git a/src/main/sensors/initialisation.c b/src/main/sensors/initialisation.c index 3d85b346a..965a81656 100755 --- a/src/main/sensors/initialisation.c +++ b/src/main/sensors/initialisation.c @@ -390,6 +390,9 @@ retry: static void detectBaro() { #ifdef BARO +#ifdef USE_BARO_BMP085 + bmp085Disable(); +#endif #ifdef USE_BARO_MS5611 // Detect what pressure sensors are available. baro->update() is set to sensor-specific update function if (ms5611Detect(&baro)) {