From ad1b7dd2164f5b0e4e63dfdc6c87b962cbfb2b85 Mon Sep 17 00:00:00 2001 From: Dominic Clifton Date: Sun, 8 Jun 2014 12:28:38 +0100 Subject: [PATCH] Update Olimexo to support a 10DOF board. Sensors on it are: MPU6050 HMC5883L BMP085. BMP085 not connected to GPIO pins. --- Makefile | 2 ++ src/main/drivers/barometer_bmp085.c | 16 ++++++++++------ src/main/sensors/initialisation.c | 21 +++++++++++++++------ src/main/target/OLIMEXINO/target.h | 6 ++++-- 4 files changed, 31 insertions(+), 14 deletions(-) diff --git a/Makefile b/Makefile index 8430c53ead..d1c07d814a 100644 --- a/Makefile +++ b/Makefile @@ -198,8 +198,10 @@ OLIMEXINO_SRC = startup_stm32f10x_md_gcc.S \ drivers/accgyro_mpu6050.c \ drivers/adc.c \ drivers/adc_stm32f10x.c \ + drivers/barometer_bmp085.c \ drivers/bus_i2c_stm32f10x.c \ drivers/bus_spi.c \ + drivers/compass_hmc5883l.c \ drivers/gpio_stm32f10x.c \ drivers/light_led_stm32f10x.c \ drivers/pwm_mapping.c \ diff --git a/src/main/drivers/barometer_bmp085.c b/src/main/drivers/barometer_bmp085.c index 9b395c3d5a..a9c4a10cf6 100755 --- a/src/main/drivers/barometer_bmp085.c +++ b/src/main/drivers/barometer_bmp085.c @@ -30,8 +30,10 @@ 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) @@ -111,9 +113,6 @@ static void bmp085_calculate(int32_t *pressure, int32_t *temperature); bool bmp085Detect(baro_t *baro) { - gpio_config_t gpio; - EXTI_InitTypeDef EXTI_InitStructure; - NVIC_InitTypeDef NVIC_InitStructure; uint8_t data; // Not supported with this frequency @@ -123,6 +122,11 @@ bool bmp085Detect(baro_t *baro) if (bmp085InitDone) return true; +#if defined(BARO) && defined(BARO_GPIO) + EXTI_InitTypeDef EXTI_InitStructure; + NVIC_InitTypeDef NVIC_InitStructure; + gpio_config_t gpio; + RCC_APB2PeriphClockCmd(RCC_APB2Periph_GPIOC, ENABLE); // PC13, PC14 (Barometer XCLR reset output, EOC input) @@ -133,9 +137,7 @@ bool bmp085Detect(baro_t *baro) gpio.pin = Pin_14; gpio.mode = Mode_IN_FLOATING; gpioInit(GPIOC, &gpio); -#ifdef BARO BARO_ON; -#endif // EXTI interrupt for barometer EOC gpioExtiLineConfig(GPIO_PortSourceGPIOC, GPIO_PinSource14); @@ -153,6 +155,7 @@ bool bmp085Detect(baro_t *baro) 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. +#endif i2cRead(BMP085_I2C_ADDR, BMP085_CHIP_ID__REG, 1, &data); /* read Chip Id */ bmp085.chip_id = BMP085_GET_BITSLICE(data, BMP085_CHIP_ID); @@ -173,7 +176,8 @@ bool bmp085Detect(baro_t *baro) baro->calculate = bmp085_calculate; return true; } -#ifdef BARO + +#if defined(BARO) && defined(BARO_GPIO) BARO_OFF; #endif return false; diff --git a/src/main/sensors/initialisation.c b/src/main/sensors/initialisation.c index 8bc59e06a0..297f9f845f 100755 --- a/src/main/sensors/initialisation.c +++ b/src/main/sensors/initialisation.c @@ -63,6 +63,8 @@ #define USE_ACC_MMA8452 #define USE_ACC_LSM303DLHC #define USE_ACC_MPU6050 +#define USE_BARO_MS5611 +#define USE_BARO_BMP085 #ifdef NAZE #undef USE_ACC_LSM303DLHC @@ -92,6 +94,7 @@ #undef USE_ACC_BMA280 #undef USE_ACC_MMA8452 #undef USE_ACC_ADXL345 +#undef USE_BARO_MS5611 #endif #ifdef CHEBUZZF3 @@ -281,15 +284,21 @@ retry: static void detectBaro() { #ifdef BARO +#ifdef USE_BARO_MS5611 // Detect what pressure sensors are available. baro->update() is set to sensor-specific update function - if (!ms5611Detect(&baro)) { - // ms5611 disables BMP085, and tries to initialize + check PROM crc. if this works, we have a baro - if (!bmp085Detect(&baro)) { - // if both failed, we don't have anything - sensorsClear(SENSOR_BARO); - } + 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)) { + return; + } +#endif + sensorsClear(SENSOR_BARO); +#endif } void reconfigureAlignment(sensorAlignmentConfig_t *sensorAlignmentConfig) diff --git a/src/main/target/OLIMEXINO/target.h b/src/main/target/OLIMEXINO/target.h index d1755c90be..6b0976d7ad 100644 --- a/src/main/target/OLIMEXINO/target.h +++ b/src/main/target/OLIMEXINO/target.h @@ -35,7 +35,9 @@ #define LED1 #endif -#define GYRO #define ACC +#define BARO +#define GYRO +#define MAG -#define SENSORS_SET (SENSOR_ACC) +#define SENSORS_SET (SENSOR_ACC | SENSOR_BARO | SENSOR_MAG)