From b6232573c06921cece33a05dac984fc5d9875ab5 Mon Sep 17 00:00:00 2001 From: Dominic Clifton Date: Thu, 17 Apr 2014 12:33:59 +0100 Subject: [PATCH] Update compass drivers so they do not include "board.h". It is now clear what all compass drivers need to compile and what was unnecessarily included before. LED macros now moved into light_led.h --- src/board.h | 22 +--------------------- src/boardalignment.h | 1 - src/drivers/accgyro_adxl345.c | 8 +++----- src/drivers/accgyro_bma280.c | 2 -- src/drivers/accgyro_common.h | 12 +----------- src/drivers/accgyro_fy90q.c | 4 ---- src/drivers/accgyro_mma845x.c | 1 - src/drivers/accgyro_mpu6050.c | 1 - src/drivers/compass_hmc5883l.c | 17 ++++++++++++++++- src/drivers/light_led.h | 22 ++++++++++++++++++++++ src/sensors_common.h | 12 ++++++++++++ 11 files changed, 55 insertions(+), 47 deletions(-) create mode 100644 src/drivers/light_led.h diff --git a/src/board.h b/src/board.h index 6b9344e373..f898e22785 100755 --- a/src/board.h +++ b/src/board.h @@ -118,27 +118,7 @@ typedef uint16_t (* rcReadRawDataPtr)(uint8_t chan); // used by receiver typedef void (* pidControllerFuncPtr)(void); // pid controller function prototype #include "platform.h" - -// Helpful macros -#ifdef LED0 -#define LED0_TOGGLE digitalToggle(LED0_GPIO, LED0_PIN); -#define LED0_OFF digitalHi(LED0_GPIO, LED0_PIN); -#define LED0_ON digitalLo(LED0_GPIO, LED0_PIN); -#else -#define LED0_TOGGLE -#define LED0_OFF -#define LED0_ON -#endif - -#ifdef LED1 -#define LED1_TOGGLE digitalToggle(LED1_GPIO, LED1_PIN); -#define LED1_OFF digitalHi(LED1_GPIO, LED1_PIN); -#define LED1_ON digitalLo(LED1_GPIO, LED1_PIN); -#else -#define LED1_TOGGLE -#define LED1_OFF -#define LED1_ON -#endif +#include "drivers/light_led.h" #ifdef BEEP_GPIO #define BEEP_TOGGLE digitalToggle(BEEP_GPIO, BEEP_PIN); diff --git a/src/boardalignment.h b/src/boardalignment.h index e995adfd21..20cf27d27a 100644 --- a/src/boardalignment.h +++ b/src/boardalignment.h @@ -1,5 +1,4 @@ #pragma once -// sensor orientation void alignSensors(int16_t *src, int16_t *dest, uint8_t rotation); void initBoardAlignment(void); diff --git a/src/drivers/accgyro_adxl345.c b/src/drivers/accgyro_adxl345.c index 832ecead93..075266c74b 100755 --- a/src/drivers/accgyro_adxl345.c +++ b/src/drivers/accgyro_adxl345.c @@ -4,15 +4,15 @@ #include #include "accgyro_common.h" -#include - -#include "accgyro_adxl345.h" +#include "sensors_common.h" #include "system_common.h" #include "bus_i2c.h" #include "boardalignment.h" +#include "accgyro_adxl345.h" + // ADXL345, Alternative address mode 0x53 #define ADXL345_ADDRESS 0x53 @@ -42,8 +42,6 @@ #define ADXL345_RANGE_16G 0x03 #define ADXL345_FIFO_STREAM 0x80 -extern uint16_t acc_1G; - static void adxl345Init(sensor_align_e align); static void adxl345Read(int16_t *accelData); diff --git a/src/drivers/accgyro_bma280.c b/src/drivers/accgyro_bma280.c index 7dd2801efd..cb690caeec 100644 --- a/src/drivers/accgyro_bma280.c +++ b/src/drivers/accgyro_bma280.c @@ -19,8 +19,6 @@ #define BMA280_PMU_BW 0x10 #define BMA280_PMU_RANGE 0x0F -extern uint16_t acc_1G; - static void bma280Init(sensor_align_e align); static void bma280Read(int16_t *accelData); diff --git a/src/drivers/accgyro_common.h b/src/drivers/accgyro_common.h index 4bd57e8861..5b790afb94 100644 --- a/src/drivers/accgyro_common.h +++ b/src/drivers/accgyro_common.h @@ -1,13 +1,3 @@ #pragma once -typedef enum { - ALIGN_DEFAULT = 0, // driver-provided alignment - CW0_DEG = 1, - CW90_DEG = 2, - CW180_DEG = 3, - CW270_DEG = 4, - CW0_DEG_FLIP = 5, - CW90_DEG_FLIP = 6, - CW180_DEG_FLIP = 7, - CW270_DEG_FLIP = 8 -} sensor_align_e; +extern uint16_t acc_1G; diff --git a/src/drivers/accgyro_fy90q.c b/src/drivers/accgyro_fy90q.c index 5a344e69e5..f023db7174 100644 --- a/src/drivers/accgyro_fy90q.c +++ b/src/drivers/accgyro_fy90q.c @@ -12,10 +12,6 @@ #include "adc_fy90q.h" -//#include "boardalignment.h" - -extern uint16_t acc_1G; - static void adcAccRead(int16_t *accelData); static void adcGyroRead(int16_t *gyroData); static void adcDummyInit(sensor_align_e align); diff --git a/src/drivers/accgyro_mma845x.c b/src/drivers/accgyro_mma845x.c index 45ae2cc2b2..257f593493 100644 --- a/src/drivers/accgyro_mma845x.c +++ b/src/drivers/accgyro_mma845x.c @@ -61,7 +61,6 @@ #define MMA8452_CTRL_REG1_LNOISE 0x04 #define MMA8452_CTRL_REG1_ACTIVE 0x01 -extern uint16_t acc_1G; static uint8_t device_id; static sensor_align_e accAlign = CW90_DEG; diff --git a/src/drivers/accgyro_mpu6050.c b/src/drivers/accgyro_mpu6050.c index c54704879b..1bb15a2421 100644 --- a/src/drivers/accgyro_mpu6050.c +++ b/src/drivers/accgyro_mpu6050.c @@ -132,7 +132,6 @@ static void mpu6050AccRead(int16_t *accData); static void mpu6050GyroInit(sensor_align_e align); static void mpu6050GyroRead(int16_t *gyroData); -extern uint16_t acc_1G; static uint8_t mpuAccelHalf = 0; bool mpu6050Detect(sensor_t *acc, sensor_t *gyro, uint16_t lpf, uint8_t *scale) diff --git a/src/drivers/compass_hmc5883l.c b/src/drivers/compass_hmc5883l.c index 2379008683..1c302e775f 100755 --- a/src/drivers/compass_hmc5883l.c +++ b/src/drivers/compass_hmc5883l.c @@ -1,7 +1,22 @@ -#include "board.h" +#include +#include + +#include + +#include "platform.h" + +#include "system_common.h" +#include "gpio_common.h" +#include "bus_i2c.h" +#include "light_led.h" + +#include "boardalignment.h" +#include "sensors_common.h" #include "maths.h" +#include "compass_hmc5883l.h" + // HMC5883L, default address 0x1E // PB12 connected to MAG_DRDY on rev4 hardware // PC14 connected to MAG_DRDY on rev5 hardware diff --git a/src/drivers/light_led.h b/src/drivers/light_led.h new file mode 100644 index 0000000000..b031a5412a --- /dev/null +++ b/src/drivers/light_led.h @@ -0,0 +1,22 @@ +#pragma once + +// Helpful macros +#ifdef LED0 +#define LED0_TOGGLE digitalToggle(LED0_GPIO, LED0_PIN); +#define LED0_OFF digitalHi(LED0_GPIO, LED0_PIN); +#define LED0_ON digitalLo(LED0_GPIO, LED0_PIN); +#else +#define LED0_TOGGLE +#define LED0_OFF +#define LED0_ON +#endif + +#ifdef LED1 +#define LED1_TOGGLE digitalToggle(LED1_GPIO, LED1_PIN); +#define LED1_OFF digitalHi(LED1_GPIO, LED1_PIN); +#define LED1_ON digitalLo(LED1_GPIO, LED1_PIN); +#else +#define LED1_TOGGLE +#define LED1_OFF +#define LED1_ON +#endif diff --git a/src/sensors_common.h b/src/sensors_common.h index 7870a3d488..607ada19da 100644 --- a/src/sensors_common.h +++ b/src/sensors_common.h @@ -1,5 +1,17 @@ #pragma once +typedef enum { + ALIGN_DEFAULT = 0, // driver-provided alignment + CW0_DEG = 1, + CW90_DEG = 2, + CW180_DEG = 3, + CW270_DEG = 4, + CW0_DEG_FLIP = 5, + CW90_DEG_FLIP = 6, + CW180_DEG_FLIP = 7, + CW270_DEG_FLIP = 8 +} sensor_align_e; + typedef void (* sensorInitFuncPtr)(sensor_align_e align); // sensor init prototype typedef void (* sensorReadFuncPtr)(int16_t *data); // sensor read and align prototype