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

Cleanup project structure. Update unit test Makefile to place object

files in obj/test
This commit is contained in:
Dominic Clifton 2014-05-31 22:43:06 +01:00
parent fb9e3a2358
commit d19a5e7046
330 changed files with 657 additions and 638 deletions

View file

@ -3,10 +3,10 @@
#include "platform.h"
#include "drivers/gpio_common.h"
#include "drivers/timer_common.h"
#include "drivers/gpio.h"
#include "drivers/timer.h"
#include "drivers/pwm_mapping.h"
#include "flight_mixer.h"
#include "flight/mixer.h"
#include "build_config.h"

View file

@ -35,8 +35,8 @@
#include <stdlib.h>
#include "drivers/serial_common.h"
#include "serial_common.h"
#include "drivers/serial.h"
#include "io/serial.h"
#include "build_config.h"
#include "printf.h"

View file

@ -6,36 +6,36 @@
#include "build_config.h"
#include "common/axis.h"
#include "flight_common.h"
#include "flight/flight.h"
#include "drivers/accgyro_common.h"
#include "drivers/system_common.h"
#include "drivers/accgyro.h"
#include "drivers/system.h"
#include "sensors_common.h"
#include "sensors_gyro.h"
#include "sensors/sensors.h"
#include "sensors/gyro.h"
#include "statusindicator.h"
#include "sensors_acceleration.h"
#include "sensors_barometer.h"
#include "drivers/serial_common.h"
#include "serial_common.h"
#include "telemetry_common.h"
#include "io/statusindicator.h"
#include "sensors/acceleration.h"
#include "sensors/barometer.h"
#include "drivers/serial.h"
#include "io/serial.h"
#include "telemetry/telemetry.h"
#include "flight_mixer.h"
#include "boardalignment.h"
#include "battery.h"
#include "gimbal.h"
#include "escservo.h"
#include "rc_controls.h"
#include "rc_curves.h"
#include "rx_common.h"
#include "gps_common.h"
#include "failsafe.h"
#include "flight/mixer.h"
#include "sensors/boardalignment.h"
#include "io/battery.h"
#include "io/gimbal.h"
#include "io/escservo.h"
#include "io/rc_controls.h"
#include "io/rc_curves.h"
#include "rx/rx.h"
#include "io/gps.h"
#include "flight/failsafe.h"
#include "runtime_config.h"
#include "config.h"
#include "config_profile.h"
#include "config_master.h"
#include "config/runtime_config.h"
#include "config/config.h"
#include "config/config_profile.h"
#include "config/config_master.h"
void setPIDController(int type); // FIXME PID code needs to be in flight_pid.c/h

View file

@ -1,7 +1,7 @@
#include <stdbool.h>
#include <stdint.h>
#include "runtime_config.h"
#include "config/runtime_config.h"
flags_t f;

View file

@ -3,10 +3,10 @@
#include <platform.h>
#include "system_common.h"
#include "system.h"
#include "bus_i2c.h"
#include "accgyro_common.h"
#include "accgyro.h"
#include "accgyro_adxl345.h"
// ADXL345, Alternative address mode 0x53

View file

@ -5,7 +5,7 @@
#include "bus_i2c.h"
#include "accgyro_common.h"
#include "accgyro.h"
#include "accgyro_bma280.h"
// BMA280, default I2C address mode 0x18

View file

@ -3,13 +3,13 @@
#include <platform.h>
#include "system_common.h"
#include "system.h"
#include "bus_i2c.h"
#include "common/maths.h"
#include "common/axis.h"
#include "accgyro_common.h"
#include "accgyro.h"
#include "accgyro_l3g4200d.h"
// L3G4200D, Standard address 0x68

View file

@ -20,11 +20,11 @@
#include "common/maths.h"
#include "system_common.h"
#include "gpio_common.h"
#include "system.h"
#include "gpio.h"
#include "bus_spi.h"
#include "accgyro_common.h"
#include "accgyro.h"
#include "accgyro_l3gd20.h"
extern int16_t debug[4];

View file

@ -6,11 +6,11 @@
#include "common/maths.h"
#include "common/axis.h"
#include "system_common.h"
#include "gpio_common.h"
#include "system.h"
#include "gpio.h"
#include "bus_i2c.h"
#include "accgyro_common.h"
#include "accgyro.h"
#include "accgyro_lsm303dlhc.h"
extern int16_t debug[4];

View file

@ -3,11 +3,11 @@
#include "platform.h"
#include "system_common.h"
#include "gpio_common.h"
#include "system.h"
#include "gpio.h"
#include "bus_i2c.h"
#include "accgyro_common.h"
#include "accgyro.h"
#include "accgyro_mma845x.h"
// MMA8452QT, Standard address 0x1C

View file

@ -5,10 +5,10 @@
#include "common/maths.h"
#include "system_common.h"
#include "system.h"
#include "bus_i2c.h"
#include "accgyro_common.h"
#include "accgyro.h"
#include "accgyro_mpu3050.h"

View file

@ -5,11 +5,11 @@
#include "common/maths.h"
#include "system_common.h"
#include "gpio_common.h"
#include "system.h"
#include "gpio.h"
#include "bus_i2c.h"
#include "accgyro_common.h"
#include "accgyro.h"
#include "accgyro_mpu6050.h"
// MPU6050, Standard address 0x68

View file

@ -2,11 +2,11 @@
#include <stdint.h>
#include "platform.h"
#include "system_common.h"
#include "system.h"
#include "accgyro_common.h"
#include "accgyro.h"
#include "adc_common.h"
#include "adc.h"
adc_config_t adcConfig[ADC_CHANNEL_COUNT];
volatile uint16_t adcValues[ADC_CHANNEL_COUNT];

View file

@ -3,13 +3,13 @@
#include <string.h>
#include "platform.h"
#include "system_common.h"
#include "system.h"
#include "sensors_common.h" // FIXME dependency into the main code
#include "sensors/sensors.h" // FIXME dependency into the main code
#include "accgyro_common.h"
#include "accgyro.h"
#include "adc_common.h"
#include "adc.h"
// Driver for STM32F103CB onboard ADC
//

View file

@ -2,15 +2,15 @@
#include <stdint.h>
#include "platform.h"
#include "system_common.h"
#include "system.h"
#include "gpio_common.h"
#include "gpio.h"
#include "sensors_common.h" // FIXME dependency into the main code
#include "sensors/sensors.h" // FIXME dependency into the main code
#include "accgyro_common.h"
#include "accgyro.h"
#include "adc_common.h"
#include "adc.h"
extern adc_config_t adcConfig[ADC_CHANNEL_COUNT];
extern volatile uint16_t adcValues[ADC_CHANNEL_COUNT];

View file

@ -3,10 +3,10 @@
#include <platform.h>
#include "barometer_common.h"
#include "barometer.h"
#include "gpio_common.h"
#include "system_common.h"
#include "gpio.h"
#include "system.h"
#include "bus_i2c.h"
// BMP085, Standard address 0x77

View file

@ -3,10 +3,10 @@
#include <platform.h>
#include "barometer_common.h"
#include "barometer.h"
#include "gpio_common.h"
#include "system_common.h"
#include "gpio.h"
#include "system.h"
#include "bus_i2c.h"
// MS5611, Standard address 0x77

View file

@ -5,7 +5,7 @@
#include "build_config.h"
#include "gpio_common.h"
#include "gpio.h"
// Software I2C driver, using same pins as hardware I2C, with hw i2c module disabled.
// SCL PB10

View file

@ -5,8 +5,8 @@
#include "build_config.h"
#include "gpio_common.h"
#include "system_common.h"
#include "gpio.h"
#include "system.h"
#include "bus_i2c.h"

View file

@ -5,8 +5,8 @@
#include "build_config.h"
#include "gpio_common.h"
#include "system_common.h"
#include "gpio.h"
#include "system.h"
#include "bus_i2c.h"

View file

@ -3,7 +3,7 @@
#include <platform.h>
#include "gpio_common.h"
#include "gpio.h"
#include "bus_spi.h"

View file

@ -9,13 +9,13 @@
#include "common/axis.h"
#include "common/maths.h"
#include "system_common.h"
#include "gpio_common.h"
#include "system.h"
#include "gpio.h"
#include "bus_i2c.h"
#include "light_led.h"
#include "boardalignment.h"
#include "sensors_common.h"
#include "sensors/boardalignment.h"
#include "sensors/sensors.h"
#include "compass_hmc5883l.h"

View file

@ -4,7 +4,7 @@
#include "platform.h"
#include "gpio_common.h"
#include "gpio.h"
void gpioInit(GPIO_TypeDef *gpio, gpio_config_t *config)
{

View file

@ -4,7 +4,7 @@
#include "platform.h"
#include "gpio_common.h"
#include "gpio.h"
#define MODE_OFFSET 0
#define PUPD_OFFSET 2

View file

@ -10,10 +10,10 @@
#include "bus_i2c.h"
// FIXME there should be no dependencies on the main source code
#include "escservo.h"
#include "rc_controls.h"
#include "sensors_common.h"
#include "flight_common.h"
#include "io/escservo.h"
#include "io/rc_controls.h"
#include "sensors/sensors.h"
#include "flight/flight.h"
#include "light_ledring.h"

View file

@ -6,8 +6,8 @@
#include "platform.h"
#include "gpio_common.h"
#include "timer_common.h"
#include "gpio.h"
#include "timer.h"
#include "pwm_output.h"
#include "pwm_rssi.h"

View file

@ -5,10 +5,10 @@
#include "platform.h"
#include "gpio_common.h"
#include "timer_common.h"
#include "gpio.h"
#include "timer.h"
#include "failsafe.h" // FIXME dependency into the main code from a driver
#include "flight/failsafe.h" // FIXME dependency into the main code from a driver
#include "pwm_mapping.h"

View file

@ -5,8 +5,8 @@
#include "platform.h"
#include "gpio_common.h"
#include "timer_common.h"
#include "gpio.h"
#include "timer.h"
#include "pwm_mapping.h"

View file

@ -5,8 +5,8 @@
#include "platform.h"
#include "gpio_common.h"
#include "timer_common.h"
#include "gpio.h"
#include "timer.h"
#include "pwm_mapping.h"

View file

@ -3,7 +3,7 @@
#include "platform.h"
#include "serial_common.h"
#include "serial.h"
void serialPrint(serialPort_t *instance, const char *str)
{

View file

@ -4,11 +4,11 @@
#include "platform.h"
#include "system_common.h"
#include "gpio_common.h"
#include "timer_common.h"
#include "system.h"
#include "gpio.h"
#include "timer.h"
#include "serial_common.h"
#include "serial.h"
#include "serial_softserial.h"
#if defined(STM32F10X_MD) || defined(CHEBUZZF3)

View file

@ -9,8 +9,8 @@
#include "platform.h"
#include "serial_common.h"
#include "serial_uart_common.h"
#include "serial.h"
#include "serial_uart.h"
uartPort_t *serialUSART1(uint32_t baudRate, portMode_t mode);
uartPort_t *serialUSART2(uint32_t baudRate, portMode_t mode);

View file

@ -11,11 +11,11 @@
#include "platform.h"
#include "system_common.h"
#include "gpio_common.h"
#include "system.h"
#include "gpio.h"
#include "serial_common.h"
#include "serial_uart_common.h"
#include "serial.h"
#include "serial_uart.h"
static uartPort_t uartPort1;
static uartPort_t uartPort2;

View file

@ -12,11 +12,11 @@
#include "platform.h"
#include "system_common.h"
#include "gpio_common.h"
#include "system.h"
#include "gpio.h"
#include "serial_common.h"
#include "serial_uart_common.h"
#include "serial.h"
#include "serial_uart.h"
// Using RX DMA disables the use of receive callbacks
#define USE_USART1_RX_DMA

View file

@ -4,8 +4,8 @@
#include "platform.h"
#include "system_common.h"
#include "gpio_common.h"
#include "system.h"
#include "gpio.h"
#include "sonar_hcsr04.h"

View file

@ -5,8 +5,8 @@
#include "platform.h"
#include "system_common.h"
#include "gpio_common.h"
#include "system.h"
#include "gpio.h"
#include "sound_beeper.h"

View file

@ -5,13 +5,13 @@
#include "platform.h"
#include "gpio_common.h"
#include "gpio.h"
#include "light_led.h"
#include "sound_beeper.h"
#include "bus_i2c.h"
#include "bus_spi.h"
#include "system_common.h"
#include "system.h"
// cycles per microsecond
static volatile uint32_t usTicks = 0;

View file

@ -6,10 +6,10 @@
#include "platform.h"
#include "gpio_common.h"
#include "system_common.h"
#include "gpio.h"
#include "system.h"
#include "timer_common.h"
#include "timer.h"
/* FreeFlight/Naze32 timer layout
TIM2_CH1 RC1 PWM1

View file

@ -6,9 +6,9 @@
#include "common/axis.h"
#include "common/maths.h"
#include "drivers/system_common.h"
#include "drivers/system.h"
#include "flight_common.h"
#include "flight/flight.h"
extern int16_t debug[4];

View file

@ -3,12 +3,12 @@
#include "common/axis.h"
#include "escservo.h"
#include "rc_controls.h"
#include "rx_common.h"
#include "runtime_config.h"
#include "io/escservo.h"
#include "io/rc_controls.h"
#include "rx/rx.h"
#include "config/runtime_config.h"
#include "failsafe.h"
#include "flight/failsafe.h"
/*
* Usage:

View file

@ -5,15 +5,15 @@
#include "common/axis.h"
#include "common/maths.h"
#include "runtime_config.h"
#include "config/runtime_config.h"
#include "drivers/accgyro_common.h"
#include "sensors_common.h"
#include "sensors_gyro.h"
#include "rc_controls.h"
#include "flight_common.h"
#include "flight_autotune.h"
#include "gps_common.h"
#include "drivers/accgyro.h"
#include "sensors/sensors.h"
#include "sensors/gyro.h"
#include "io/rc_controls.h"
#include "flight/flight.h"
#include "flight/autotune.h"
#include "io/gps.h"
extern uint16_t cycleTime;

View file

@ -9,36 +9,36 @@
#include <platform.h>
#include "common/axis.h"
#include "flight_common.h"
#include "flight/flight.h"
#include "drivers/system_common.h"
#include "drivers/system.h"
#include "sensors_common.h"
#include "drivers/accgyro_common.h"
#include "sensors_gyro.h"
#include "sensors_compass.h"
#include "sensors_acceleration.h"
#include "sensors_barometer.h"
#include "sensors/sensors.h"
#include "drivers/accgyro.h"
#include "sensors/gyro.h"
#include "sensors/compass.h"
#include "sensors/acceleration.h"
#include "sensors/barometer.h"
#include "gps_common.h"
#include "io/gps.h"
#include "gimbal.h"
#include "flight_mixer.h"
#include "io/gimbal.h"
#include "flight/mixer.h"
// FIXME remove dependency on config.h
#include "boardalignment.h"
#include "battery.h"
#include "escservo.h"
#include "rc_controls.h"
#include "rx_common.h"
#include "drivers/serial_common.h"
#include "serial_common.h"
#include "telemetry_common.h"
#include "failsafe.h"
#include "runtime_config.h"
#include "config.h"
#include "config_profile.h"
#include "config_master.h"
#include "sensors/boardalignment.h"
#include "io/battery.h"
#include "io/escservo.h"
#include "io/rc_controls.h"
#include "rx/rx.h"
#include "drivers/serial.h"
#include "io/serial.h"
#include "telemetry/telemetry.h"
#include "flight/failsafe.h"
#include "config/runtime_config.h"
#include "config/config.h"
#include "config/config_profile.h"
#include "config/config_master.h"
int16_t gyroADC[XYZ_AXIS_COUNT], accADC[XYZ_AXIS_COUNT], accSmooth[XYZ_AXIS_COUNT];

View file

@ -7,20 +7,20 @@
#include "common/axis.h"
#include "common/maths.h"
#include "drivers/gpio_common.h"
#include "drivers/timer_common.h"
#include "drivers/gpio.h"
#include "drivers/timer.h"
#include "drivers/pwm_output.h"
#include "gimbal.h"
#include "escservo.h"
#include "rc_controls.h"
#include "rx_common.h"
#include "io/gimbal.h"
#include "io/escservo.h"
#include "io/rc_controls.h"
#include "rx/rx.h"
#include "flight_mixer.h"
#include "flight_common.h"
#include "flight/mixer.h"
#include "flight/flight.h"
#include "runtime_config.h"
#include "config.h"
#include "config/runtime_config.h"
#include "config/config.h"
static uint8_t numberMotor = 0;

View file

@ -1,10 +1,10 @@
#include "stdbool.h"
#include "stdint.h"
#include "drivers/adc_common.h"
#include "drivers/system_common.h"
#include "drivers/adc.h"
#include "drivers/system.h"
#include "battery.h"
#include "io/battery.h"
// Battery monitoring stuff
uint8_t batteryCellCount = 3; // cell count

View file

@ -3,13 +3,13 @@
#include "platform.h"
#include "drivers/sound_beeper.h"
#include "drivers/system_common.h"
#include "failsafe.h"
#include "sensors_common.h"
#include "runtime_config.h"
#include "config.h"
#include "drivers/system.h"
#include "flight/failsafe.h"
#include "sensors/sensors.h"
#include "config/runtime_config.h"
#include "config/config.h"
#include "buzzer.h"
#include "io/buzzer.h"
#define DOUBLE_PAUSE_DURATION_MILLIS (LONG_PAUSE_DURATION_MILLIS * 2)
#define LONG_PAUSE_DURATION_MILLIS 400

View file

@ -8,25 +8,25 @@
#include "common/maths.h"
#include "drivers/system_common.h"
#include "drivers/system.h"
#include "drivers/serial_common.h"
#include "drivers/serial_uart_common.h"
#include "serial_common.h"
#include "drivers/serial.h"
#include "drivers/serial_uart.h"
#include "io/serial.h"
#include "drivers/gpio_common.h"
#include "drivers/gpio.h"
#include "drivers/light_led.h"
#include "common/axis.h"
#include "flight_common.h"
#include "flight/flight.h"
#include "sensors_common.h"
#include "sensors/sensors.h"
#include "config.h"
#include "runtime_config.h"
#include "config/config.h"
#include "config/runtime_config.h"
#include "gps_conversion.h"
#include "gps_common.h"
#include "io/gps.h"
extern int16_t debug[4];

View file

@ -5,7 +5,7 @@
#include "common/maths.h"
#include "rc_controls.h"
#include "io/rc_controls.h"
int16_t rcCommand[4]; // interval [1000;2000] for THROTTLE and [-500;+500] for ROLL/PITCH/YAW

Some files were not shown because too many files have changed in this diff Show more