Decouple ms5611 baro driver from bmp085 driver.
This commit is contained in:
parent
a12cf4ae59
commit
6013d9dc6a
|
@ -116,6 +116,25 @@ static int32_t bmp085_get_temperature(uint32_t ut);
|
||||||
static int32_t bmp085_get_pressure(uint32_t up);
|
static int32_t bmp085_get_pressure(uint32_t up);
|
||||||
static void bmp085_calculate(int32_t *pressure, int32_t *temperature);
|
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)
|
bool bmp085Detect(baro_t *baro)
|
||||||
{
|
{
|
||||||
uint8_t data;
|
uint8_t data;
|
||||||
|
|
|
@ -18,3 +18,4 @@
|
||||||
#pragma once
|
#pragma once
|
||||||
|
|
||||||
bool bmp085Detect(baro_t *baro);
|
bool bmp085Detect(baro_t *baro);
|
||||||
|
void bmp085Disable(void);
|
||||||
|
|
|
@ -28,9 +28,6 @@
|
||||||
|
|
||||||
// MS5611, Standard address 0x77
|
// MS5611, Standard address 0x77
|
||||||
#define MS5611_ADDR 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_RESET 0x1E // ADC reset command
|
||||||
#define CMD_ADC_READ 0x00 // ADC read command
|
#define CMD_ADC_READ 0x00 // ADC read command
|
||||||
|
@ -66,22 +63,8 @@ bool ms5611Detect(baro_t *baro)
|
||||||
uint8_t sig;
|
uint8_t sig;
|
||||||
int i;
|
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
|
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);
|
ack = i2cRead(MS5611_ADDR, CMD_PROM_RD, 1, &sig);
|
||||||
if (!ack)
|
if (!ack)
|
||||||
return false;
|
return false;
|
||||||
|
|
|
@ -390,6 +390,9 @@ retry:
|
||||||
static void detectBaro()
|
static void detectBaro()
|
||||||
{
|
{
|
||||||
#ifdef BARO
|
#ifdef BARO
|
||||||
|
#ifdef USE_BARO_BMP085
|
||||||
|
bmp085Disable();
|
||||||
|
#endif
|
||||||
#ifdef USE_BARO_MS5611
|
#ifdef USE_BARO_MS5611
|
||||||
// Detect what pressure sensors are available. baro->update() is set to sensor-specific update function
|
// Detect what pressure sensors are available. baro->update() is set to sensor-specific update function
|
||||||
if (ms5611Detect(&baro)) {
|
if (ms5611Detect(&baro)) {
|
||||||
|
|
Loading…
Reference in New Issue