1
0
Fork 0
mirror of https://github.com/betaflight/betaflight.git synced 2025-07-17 05:15:25 +03:00

Relocate common code which can be used by drivers and by main into

'common'.  Cleanup includes.  Fix FY90Q target compilation.
This commit is contained in:
Dominic Clifton 2014-04-17 23:50:13 +01:00
parent d4ebd8a748
commit f06c8bb99b
19 changed files with 41 additions and 36 deletions

View file

@ -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 \

View file

@ -16,12 +16,14 @@
#include <stdio.h>
#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"

View file

@ -1,10 +1,10 @@
#include "stdbool.h"
#include "stdint.h"
#include <stdbool.h>
#include <stdint.h>
#include <math.h>
#include "math.h"
#include "common/maths.h"
#include "common/axis.h"
#include "maths.h"
#include "axis.h"
#include "sensors_common.h"
#include "boardalignment.h"

View file

@ -3,10 +3,10 @@
#include <platform.h>
#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

View file

@ -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

View file

@ -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

View file

@ -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"

View file

@ -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

View file

@ -1,12 +1,12 @@
#include <stdbool.h>
#include <stdint.h>
#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

View file

@ -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];

View file

@ -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];

View file

@ -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"

View file

@ -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

View file

@ -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]

View file

@ -1,7 +1,7 @@
#include "board.h"
#include "mw.h"
#include "axis.h"
#include "common/axis.h"
int16_t magADC[XYZ_AXIS_COUNT];

View file

@ -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)
{