Use Naze hardware revision when initialising bmp085. Cleanup bmp085
GPIO configuration for all targets.
This commit is contained in:
parent
79917da85a
commit
2ed09b0b2f
|
@ -20,21 +20,20 @@
|
|||
|
||||
#include <platform.h>
|
||||
|
||||
#include "build_config.h"
|
||||
|
||||
#include "barometer.h"
|
||||
|
||||
#include "gpio.h"
|
||||
#include "system.h"
|
||||
#include "bus_i2c.h"
|
||||
|
||||
#include "barometer_bmp085.h"
|
||||
|
||||
// BMP085, Standard address 0x77
|
||||
static bool convDone = false;
|
||||
static uint16_t convOverrun = 0;
|
||||
|
||||
#ifdef BARO_GPIO
|
||||
#define BARO_OFF digitalLo(BARO_GPIO, BARO_PIN);
|
||||
#define BARO_ON digitalHi(BARO_GPIO, BARO_PIN);
|
||||
#endif
|
||||
|
||||
// EXTI14 for BMP085 End of Conversion Interrupt
|
||||
void EXTI15_10_IRQHandler(void)
|
||||
{
|
||||
|
@ -116,75 +115,73 @@ 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);
|
||||
|
||||
#ifdef BARO_PIN
|
||||
#define BMP085_OFF digitalLo(BARO_GPIO, BARO_PIN);
|
||||
#define BMP085_ON digitalHi(BARO_GPIO, BARO_PIN);
|
||||
#ifdef BARO_XCLR_PIN
|
||||
#define BMP085_OFF digitalLo(BARO_XCLR_GPIO, BARO_XCLR_PIN);
|
||||
#define BMP085_ON digitalHi(BARO_XCLR_GPIO, BARO_XCLR_PIN);
|
||||
#else
|
||||
#define BMP085_OFF
|
||||
#define BMP085_ON
|
||||
#endif
|
||||
|
||||
void bmp085Disable(void)
|
||||
{
|
||||
if (hse_value != 12000000) {
|
||||
RCC_APB2PeriphClockCmd(RCC_APB2Periph_GPIOC, ENABLE);
|
||||
void bmp085InitXCLRGpio(const bmp085Config_t *config) {
|
||||
gpio_config_t gpio;
|
||||
|
||||
// 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);
|
||||
}
|
||||
RCC_APB2PeriphClockCmd(config->gpioAPB2Peripherals, ENABLE);
|
||||
|
||||
// PC13, PC14 (Barometer XCLR reset output, EOC input)
|
||||
gpio.pin = config->xclrGpioPin;
|
||||
gpio.speed = Speed_2MHz;
|
||||
gpio.mode = Mode_Out_PP;
|
||||
gpioInit(config->xclrGpioPort, &gpio);
|
||||
}
|
||||
|
||||
void bmp085Disable(const bmp085Config_t *config)
|
||||
{
|
||||
bmp085InitXCLRGpio(config);
|
||||
BMP085_OFF;
|
||||
}
|
||||
|
||||
bool bmp085Detect(baro_t *baro)
|
||||
bool bmp085Detect(const bmp085Config_t *config, baro_t *baro)
|
||||
{
|
||||
uint8_t data;
|
||||
|
||||
// Not supported with this frequency
|
||||
if (hse_value == 12000000)
|
||||
return false;
|
||||
|
||||
if (bmp085InitDone)
|
||||
return true;
|
||||
|
||||
#if defined(BARO) && defined(BARO_GPIO)
|
||||
EXTI_InitTypeDef EXTI_InitStructure;
|
||||
NVIC_InitTypeDef NVIC_InitStructure;
|
||||
gpio_config_t gpio;
|
||||
#if defined(BARO) && defined(BARO_XCLR_GPIO) && defined(BARO_EOC_GPIO)
|
||||
if (config) {
|
||||
EXTI_InitTypeDef EXTI_InitStructure;
|
||||
NVIC_InitTypeDef NVIC_InitStructure;
|
||||
gpio_config_t gpio;
|
||||
|
||||
RCC_APB2PeriphClockCmd(RCC_APB2Periph_GPIOC, ENABLE);
|
||||
bmp085InitXCLRGpio(config);
|
||||
|
||||
// PC13, PC14 (Barometer XCLR reset output, EOC input)
|
||||
gpio.pin = Pin_13;
|
||||
gpio.speed = Speed_2MHz;
|
||||
gpio.mode = Mode_Out_PP;
|
||||
gpioInit(GPIOC, &gpio);
|
||||
gpio.pin = Pin_14;
|
||||
gpio.mode = Mode_IN_FLOATING;
|
||||
gpioInit(GPIOC, &gpio);
|
||||
BARO_ON;
|
||||
gpio.pin = config->eocGpioPin;
|
||||
gpio.mode = Mode_IN_FLOATING;
|
||||
gpioInit(config->eocGpioPort, &gpio);
|
||||
BMP085_ON;
|
||||
|
||||
// EXTI interrupt for barometer EOC
|
||||
gpioExtiLineConfig(GPIO_PortSourceGPIOC, GPIO_PinSource14);
|
||||
EXTI_InitStructure.EXTI_Line = EXTI_Line14;
|
||||
EXTI_InitStructure.EXTI_Mode = EXTI_Mode_Interrupt;
|
||||
EXTI_InitStructure.EXTI_Trigger = EXTI_Trigger_Rising;
|
||||
EXTI_InitStructure.EXTI_LineCmd = ENABLE;
|
||||
EXTI_Init(&EXTI_InitStructure);
|
||||
// EXTI interrupt for barometer EOC
|
||||
gpioExtiLineConfig(GPIO_PortSourceGPIOC, GPIO_PinSource14);
|
||||
EXTI_InitStructure.EXTI_Line = EXTI_Line14;
|
||||
EXTI_InitStructure.EXTI_Mode = EXTI_Mode_Interrupt;
|
||||
EXTI_InitStructure.EXTI_Trigger = EXTI_Trigger_Rising;
|
||||
EXTI_InitStructure.EXTI_LineCmd = ENABLE;
|
||||
EXTI_Init(&EXTI_InitStructure);
|
||||
|
||||
// Enable and set EXTI10-15 Interrupt to the lowest priority
|
||||
NVIC_InitStructure.NVIC_IRQChannel = EXTI15_10_IRQn;
|
||||
NVIC_InitStructure.NVIC_IRQChannelPreemptionPriority = 0x0F;
|
||||
NVIC_InitStructure.NVIC_IRQChannelSubPriority = 0x0F;
|
||||
NVIC_InitStructure.NVIC_IRQChannelCmd = ENABLE;
|
||||
NVIC_Init(&NVIC_InitStructure);
|
||||
|
||||
delay(20); // datasheet says 10ms, we'll be careful and do 20. this is after ms5611 driver kills us, so longer the better.
|
||||
// Enable and set EXTI10-15 Interrupt to the lowest priority
|
||||
NVIC_InitStructure.NVIC_IRQChannel = EXTI15_10_IRQn;
|
||||
NVIC_InitStructure.NVIC_IRQChannelPreemptionPriority = 0x0F;
|
||||
NVIC_InitStructure.NVIC_IRQChannelSubPriority = 0x0F;
|
||||
NVIC_InitStructure.NVIC_IRQChannelCmd = ENABLE;
|
||||
NVIC_Init(&NVIC_InitStructure);
|
||||
}
|
||||
#else
|
||||
UNUSED(config);
|
||||
#endif
|
||||
|
||||
delay(20); // datasheet says 10ms, we'll be careful and do 20.
|
||||
|
||||
i2cRead(BMP085_I2C_ADDR, BMP085_CHIP_ID__REG, 1, &data); /* read Chip Id */
|
||||
bmp085.chip_id = BMP085_GET_BITSLICE(data, BMP085_CHIP_ID);
|
||||
bmp085.oversampling_setting = 3;
|
||||
|
@ -205,9 +202,8 @@ bool bmp085Detect(baro_t *baro)
|
|||
return true;
|
||||
}
|
||||
|
||||
#if defined(BARO) && defined(BARO_GPIO)
|
||||
BARO_OFF;
|
||||
#endif
|
||||
BMP085_OFF;
|
||||
|
||||
return false;
|
||||
}
|
||||
|
||||
|
|
|
@ -17,5 +17,13 @@
|
|||
|
||||
#pragma once
|
||||
|
||||
bool bmp085Detect(baro_t *baro);
|
||||
void bmp085Disable(void);
|
||||
typedef struct bmp085Config_s {
|
||||
uint32_t gpioAPB2Peripherals;
|
||||
uint16_t xclrGpioPin;
|
||||
GPIO_TypeDef *xclrGpioPort;
|
||||
uint16_t eocGpioPin;
|
||||
GPIO_TypeDef *eocGpioPort;
|
||||
} bmp085Config_t;
|
||||
|
||||
bool bmp085Detect(const bmp085Config_t *config, baro_t *baro);
|
||||
void bmp085Disable(const bmp085Config_t *config);
|
||||
|
|
|
@ -20,6 +20,8 @@
|
|||
|
||||
#include <platform.h>
|
||||
|
||||
#include "build_config.h"
|
||||
|
||||
#include "gpio.h"
|
||||
|
||||
#include "bus_spi.h"
|
||||
|
@ -133,6 +135,10 @@ void initSpi2(void)
|
|||
|
||||
bool spiInit(SPI_TypeDef *instance)
|
||||
{
|
||||
#if (!(defined(USE_SPI_DEVICE_1) && defined(USE_SPI_DEVICE_2)))
|
||||
UNUSED(instance);
|
||||
#endif
|
||||
|
||||
#ifdef USE_SPI_DEVICE_1
|
||||
if (instance == SPI1) {
|
||||
initSpi1();
|
||||
|
|
|
@ -323,20 +323,40 @@ 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
|
||||
|
||||
#ifdef BARO
|
||||
#ifdef USE_BARO_BMP085
|
||||
|
||||
const bmp085Config_t *bmp085Config = NULL;
|
||||
|
||||
#if defined(BARO_XCLR_GPIO) && defined(BARO_EOC_GPIO)
|
||||
static const bmp085Config_t defaultBMP085Config = {
|
||||
.gpioAPB2Peripherals = BARO_APB2_PERIPHERALS,
|
||||
.xclrGpioPin = BARO_XCLR_PIN,
|
||||
.xclrGpioPort = BARO_XCLR_GPIO,
|
||||
.eocGpioPin = BARO_EOC_PIN,
|
||||
.eocGpioPort = BARO_EOC_GPIO
|
||||
};
|
||||
bmp085Config = &defaultBMP085Config;
|
||||
#endif
|
||||
|
||||
#ifdef NAZE
|
||||
if (hardwareRevision == NAZE32) {
|
||||
bmp085Disable(bmp085Config);
|
||||
}
|
||||
#endif
|
||||
|
||||
#endif
|
||||
|
||||
#ifdef USE_BARO_MS5611
|
||||
if (ms5611Detect(&baro)) {
|
||||
return;
|
||||
}
|
||||
#endif
|
||||
|
||||
#ifdef USE_BARO_BMP085
|
||||
// ms5611 disables BMP085, and tries to initialize + check PROM crc. if this works, we have a baro
|
||||
if (bmp085Detect(&baro)) {
|
||||
if (bmp085Detect(bmp085Config, &baro)) {
|
||||
return;
|
||||
}
|
||||
#endif
|
||||
|
|
|
@ -31,9 +31,6 @@
|
|||
#define BEEP_PERIPHERAL RCC_AHBPeriph_GPIOE
|
||||
#define BEEPER_INVERTED
|
||||
|
||||
#define BARO_GPIO GPIOC
|
||||
#define BARO_PIN Pin_13
|
||||
|
||||
#define GYRO
|
||||
#define USE_GYRO_L3GD20
|
||||
|
||||
|
|
|
@ -17,9 +17,6 @@
|
|||
|
||||
#pragma once
|
||||
|
||||
#define BARO_GPIO GPIOC
|
||||
#define BARO_PIN Pin_13
|
||||
|
||||
#define MPU6000_CS_GPIO GPIOB
|
||||
#define MPU6000_CS_PIN GPIO_Pin_12
|
||||
#define MPU6000_SPI_INSTANCE SPI2
|
||||
|
|
|
@ -33,8 +33,6 @@
|
|||
|
||||
|
||||
#define BEEPER_INVERTED
|
||||
#define BARO_GPIO GPIOC
|
||||
#define BARO_PIN Pin_13
|
||||
|
||||
#define GYRO
|
||||
#define ACC
|
||||
|
|
|
@ -29,8 +29,11 @@
|
|||
#define BEEP_PIN Pin_12 // PA12 (Beeper)
|
||||
#define BEEP_PERIPHERAL RCC_APB2Periph_GPIOA
|
||||
|
||||
#define BARO_GPIO GPIOC
|
||||
#define BARO_PIN Pin_13
|
||||
#define BARO_XCLR_GPIO GPIOC
|
||||
#define BARO_XCLR_PIN Pin_13
|
||||
#define BARO_EOC_GPIO GPIOC
|
||||
#define BARO_EOC_PIN Pin_14
|
||||
#define BARO_APB2_PERIPHERALS RCC_APB2Periph_GPIOC
|
||||
|
||||
#define INVERTER_PIN Pin_2 // PB2 (BOOT1) abused as inverter select GPIO
|
||||
#define INVERTER_GPIO GPIOB
|
||||
|
|
|
@ -33,8 +33,6 @@
|
|||
|
||||
|
||||
#define BEEPER_INVERTED
|
||||
#define BARO_GPIO GPIOC
|
||||
#define BARO_PIN Pin_13
|
||||
|
||||
#define GYRO
|
||||
#define USE_GYRO_L3GD20
|
||||
|
|
Loading…
Reference in New Issue