From f06c8bb99b1e9fe95a10a04fa5abf057fc1e0a15 Mon Sep 17 00:00:00 2001 From: Dominic Clifton Date: Thu, 17 Apr 2014 23:50:13 +0100 Subject: [PATCH] Relocate common code which can be used by drivers and by main into 'common'. Cleanup includes. Fix FY90Q target compilation. --- Makefile | 2 +- src/board.h | 4 +++- src/boardalignment.c | 10 +++++----- src/{ => common}/axis.h | 0 src/{ => common}/maths.c | 0 src/{ => common}/maths.h | 0 src/drivers/accgyro_l3g4200d.c | 8 ++++---- src/drivers/accgyro_mpu3050.c | 3 ++- src/drivers/accgyro_mpu6050.c | 4 ++-- src/drivers/compass_hmc5883l.c | 5 +++-- src/drivers/light_ledring.c | 5 +++-- src/failsafe.c | 4 ++-- src/flight_imu.c | 5 +++-- src/flight_mixer.c | 5 +++-- src/gps_common.c | 5 +++-- src/mw.c | 5 +++-- src/rx_common.c | 7 +------ src/sensors_compass.c | 2 +- src/sensors_gyro.c | 3 ++- 19 files changed, 41 insertions(+), 36 deletions(-) rename src/{ => common}/axis.h (100%) rename src/{ => common}/maths.c (100%) rename src/{ => common}/maths.h (100%) diff --git a/Makefile b/Makefile index e1a84bff4a..b294c75e46 100644 --- a/Makefile +++ b/Makefile @@ -47,6 +47,7 @@ COMMON_SRC = startup_stm32f10x_md_gcc.S \ boardalignment.c \ buzzer.c \ config.c \ + common/maths.c \ failsafe.c \ main.c \ mw.c \ @@ -57,7 +58,6 @@ COMMON_SRC = startup_stm32f10x_md_gcc.S \ sensors_gyro.c \ sensors_initialisation.c \ sensors_sonar.c \ - maths.c \ typeconversion.c \ drivers/bus_i2c.c \ drivers/bus_i2c_soft.c \ diff --git a/src/board.h b/src/board.h index a3bb64563f..ce156221ea 100755 --- a/src/board.h +++ b/src/board.h @@ -16,12 +16,14 @@ #include #include "platform.h" + +#include "common/axis.h" + #include "drivers/accgyro_common.h" #include "drivers/gpio_common.h" #include "drivers/system_common.h" #include "drivers/barometer_common.h" #include "sensors_common.h" -#include "axis.h" #include "platform.h" #include "drivers/light_led.h" diff --git a/src/boardalignment.c b/src/boardalignment.c index 32ccef84b5..bb1369c5ac 100644 --- a/src/boardalignment.c +++ b/src/boardalignment.c @@ -1,10 +1,10 @@ -#include "stdbool.h" -#include "stdint.h" +#include +#include +#include -#include "math.h" +#include "common/maths.h" +#include "common/axis.h" -#include "maths.h" -#include "axis.h" #include "sensors_common.h" #include "boardalignment.h" diff --git a/src/axis.h b/src/common/axis.h similarity index 100% rename from src/axis.h rename to src/common/axis.h diff --git a/src/maths.c b/src/common/maths.c similarity index 100% rename from src/maths.c rename to src/common/maths.c diff --git a/src/maths.h b/src/common/maths.h similarity index 100% rename from src/maths.h rename to src/common/maths.h diff --git a/src/drivers/accgyro_l3g4200d.c b/src/drivers/accgyro_l3g4200d.c index dec54197a9..4685f00d6f 100644 --- a/src/drivers/accgyro_l3g4200d.c +++ b/src/drivers/accgyro_l3g4200d.c @@ -3,10 +3,10 @@ #include -#include "accgyro_common.h" -#include "axis.h" -#include "sensors_common.h" +#include "common/axis.h" +#include "accgyro_common.h" +#include "sensors_common.h" #include "accgyro_l3g4200d.h" @@ -15,7 +15,7 @@ #include "boardalignment.h" -#include "maths.h" +#include "common/maths.h" // L3G4200D, Standard address 0x68 #define L3G4200D_ADDRESS 0x68 diff --git a/src/drivers/accgyro_mpu3050.c b/src/drivers/accgyro_mpu3050.c index 939fbcf39f..0ec8004d21 100755 --- a/src/drivers/accgyro_mpu3050.c +++ b/src/drivers/accgyro_mpu3050.c @@ -3,6 +3,8 @@ #include "platform.h" +#include "common/maths.h" + #include "accgyro_common.h" #include "system_common.h" @@ -14,7 +16,6 @@ #include "boardalignment.h" -#include "maths.h" // MPU3050, Standard address 0x68 #define MPU3050_ADDRESS 0x68 diff --git a/src/drivers/accgyro_mpu6050.c b/src/drivers/accgyro_mpu6050.c index 1bb15a2421..170e5b16f5 100644 --- a/src/drivers/accgyro_mpu6050.c +++ b/src/drivers/accgyro_mpu6050.c @@ -3,6 +3,8 @@ #include "platform.h" +#include "common/maths.h" + #include "accgyro_common.h" #include "system_common.h" #include "gpio_common.h" @@ -15,8 +17,6 @@ #include "boardalignment.h" -#include "maths.h" - // MPU6050, Standard address 0x68 // MPU_INT on PB13 on rev4 hardware #define MPU6050_ADDRESS 0x68 diff --git a/src/drivers/compass_hmc5883l.c b/src/drivers/compass_hmc5883l.c index 9866a971b6..f3c9f91c32 100755 --- a/src/drivers/compass_hmc5883l.c +++ b/src/drivers/compass_hmc5883l.c @@ -6,15 +6,16 @@ #include "platform.h" +#include "common/axis.h" +#include "common/maths.h" + #include "system_common.h" #include "gpio_common.h" #include "bus_i2c.h" #include "light_led.h" #include "boardalignment.h" -#include "axis.h" #include "sensors_common.h" -#include "maths.h" #include "compass_hmc5883l.h" diff --git a/src/drivers/light_ledring.c b/src/drivers/light_ledring.c index d8388af2af..4245bc94da 100644 --- a/src/drivers/light_ledring.c +++ b/src/drivers/light_ledring.c @@ -4,12 +4,13 @@ #include "platform.h" +#include "common/axis.h" +#include "common/maths.h" + #include "bus_i2c.h" #include "sensors_common.h" -#include "axis.h" #include "flight_common.h" -#include "maths.h" // Driver for DFRobot I2C Led Ring #define LED_RING_ADDRESS 0x6D diff --git a/src/failsafe.c b/src/failsafe.c index bc0955b8fb..645618e2a7 100644 --- a/src/failsafe.c +++ b/src/failsafe.c @@ -1,12 +1,12 @@ #include #include -#include "rx_common.h" +#include "common/axis.h" // FIXME this file should not have a dependency axis +#include "rx_common.h" #include "drivers/serial_common.h" // FIXME this file should not have a dependency on serial ports, see core_t from runtime_config.h #include "flight_mixer.h" // FIXME this file should not have a dependency on the flight mixer, see config_t, servoParam_t, etc from config_storage.h -#include "axis.h" // FIXME this file should not have a dependency axis #include "flight_common.h" // FIXME this file should not have a dependency on the flight common, see config_t from config_storage.h #include "sensors_common.h" // FIXME this file should not have a dependency on the sensors, see sensor_align_e from config_storage.h #include "boardalignment.h" // FIXME this file should not have a dependency on board alignment diff --git a/src/flight_imu.c b/src/flight_imu.c index 45098d5319..3703896761 100644 --- a/src/flight_imu.c +++ b/src/flight_imu.c @@ -1,11 +1,12 @@ #include "board.h" -#include "flight_common.h" #include "mw.h" -#include "maths.h" +#include "common/maths.h" #include "sensors_compass.h" +#include "flight_common.h" + int16_t gyroADC[XYZ_AXIS_COUNT], accADC[XYZ_AXIS_COUNT], accSmooth[XYZ_AXIS_COUNT]; int32_t accSum[XYZ_AXIS_COUNT]; diff --git a/src/flight_mixer.c b/src/flight_mixer.c index 4eb6ddafc5..b9dfa646d9 100755 --- a/src/flight_mixer.c +++ b/src/flight_mixer.c @@ -1,10 +1,11 @@ #include "board.h" -#include "flight_common.h" #include "mw.h" +#include "common/maths.h" + #include "rx_common.h" -#include "maths.h" +#include "flight_common.h" static uint8_t numberMotor = 0; int16_t motor[MAX_MOTORS]; diff --git a/src/gps_common.c b/src/gps_common.c index 02ab05aba1..fbe2ed65dd 100644 --- a/src/gps_common.c +++ b/src/gps_common.c @@ -1,8 +1,9 @@ #include "board.h" -#include "flight_common.h" #include "mw.h" -#include "maths.h" +#include "common/maths.h" + +#include "flight_common.h" #include "gps_common.h" diff --git a/src/mw.c b/src/mw.c index 7a0ef39444..b22e8ff4e5 100755 --- a/src/mw.c +++ b/src/mw.c @@ -1,14 +1,15 @@ #include "board.h" -#include "flight_common.h" #include "mw.h" +#include "common/maths.h" + +#include "flight_common.h" #include "serial_cli.h" #include "telemetry_common.h" #include "typeconversion.h" #include "rx_common.h" #include "rx_sbus.h" #include "failsafe.h" -#include "maths.h" // June 2013 V2.2-dev diff --git a/src/rx_common.c b/src/rx_common.c index 120ecf5c89..b4542dbb8a 100644 --- a/src/rx_common.c +++ b/src/rx_common.c @@ -7,13 +7,8 @@ #include "rx_common.h" #include "config.h" -// FIXME all includes below are just for pwmReadRawRC because it uses mcfg -#ifdef FY90Q -#include "drivers/pwm_fy90q.h" -#else #include "drivers/pwm_common.h" -#endif - + int16_t rcData[RC_CHANS]; // interval [1000;2000] diff --git a/src/sensors_compass.c b/src/sensors_compass.c index 4790f91719..4f71518ffb 100644 --- a/src/sensors_compass.c +++ b/src/sensors_compass.c @@ -1,7 +1,7 @@ #include "board.h" #include "mw.h" -#include "axis.h" +#include "common/axis.h" int16_t magADC[XYZ_AXIS_COUNT]; diff --git a/src/sensors_gyro.c b/src/sensors_gyro.c index 55fb840011..71ecbfe9b4 100644 --- a/src/sensors_gyro.c +++ b/src/sensors_gyro.c @@ -1,9 +1,10 @@ #include "board.h" #include "mw.h" +#include "common/maths.h" + #include "flight_common.h" -#include "maths.h" void GYRO_Common(void) {