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

Re-organize files by topic

Keil project not updated, I have no way to verify it.

Note, mw.c, drv_pwm.c and drv_system.c contain code for too many topics.
Later commits will relocate the code as appropriate.

Not even looked at utils yet.  'Utils' is a bad naming practice and is a
synonym for 'too lazy to find the right file/name'.
This commit is contained in:
Dominic Clifton 2014-04-08 16:11:17 +01:00
parent a8f383077c
commit 9fa99cf9f5
61 changed files with 76 additions and 6363 deletions

View file

@ -43,49 +43,49 @@ BIN_DIR = $(ROOT)/obj
# Source files common to all targets # Source files common to all targets
COMMON_SRC = startup_stm32f10x_md_gcc.S \ COMMON_SRC = startup_stm32f10x_md_gcc.S \
buzzer.c \ buzzer.c \
cli.c \ ui/cli.c \
config.c \ config.c \
gps.c \ gps/gps.c \
imu.c \ flight/imu.c \
main.c \ main.c \
mixer.c \ flight/mixer.c \
mw.c \ mw.c \
sensors.c \ sensors.c \
serial.c \ ui/serial.c \
sbus.c \ rx/sbus.c \
sumd.c \ rx/sumd.c \
spektrum.c \ rx/spektrum.c \
telemetry_common.c \ telemetry/telemetry_common.c \
telemetry_frsky.c \ telemetry/telemetry_frsky.c \
telemetry_hott.c \ telemetry/telemetry_hott.c \
drv_gpio.c \ drivers/gpio/drv_gpio.c \
drv_i2c.c \ drivers/bus/drv_i2c.c \
drv_i2c_soft.c \ drivers/bus/drv_i2c_soft.c \
drv_system.c \ drv_system.c \
drv_serial.c \ drivers/serial/drv_serial.c \
drv_softserial.c \ drivers/serial/drv_softserial.c \
drv_uart.c \ drivers/serial/drv_uart.c \
printf.c \ printf.c \
utils.c \ utils.c \
$(CMSIS_SRC) \ $(CMSIS_SRC) \
$(STDPERIPH_SRC) $(STDPERIPH_SRC)
# Source files for the NAZE target # Source files for the NAZE target
NAZE_SRC = drv_adc.c \ NAZE_SRC = drivers/adc/drv_adc.c \
drv_adxl345.c \ drivers/accgyro/drv_adxl345.c \
drv_bma280.c \ drivers/accgyro/drv_bma280.c \
drv_bmp085.c \ drivers/altimeter/drv_bmp085.c \
drv_ms5611.c \ drivers/altimeter/drv_ms5611.c \
drv_hcsr04.c \ drivers/sonar/drv_hcsr04.c \
drv_hmc5883l.c \ drivers/compass/drv_hmc5883l.c \
drv_ledring.c \ drivers/light/drv_ledring.c \
drv_mma845x.c \ drivers/accgyro/drv_mma845x.c \
drv_mpu3050.c \ drivers/accgyro/drv_mpu3050.c \
drv_mpu6050.c \ drivers/accgyro/drv_mpu6050.c \
drv_l3g4200d.c \ drivers/accgyro/drv_l3g4200d.c \
drv_pwm.c \ drv_pwm.c \
drv_spi.c \ drivers/bus/drv_spi.c \
drv_timer.c \ drivers/timer/drv_timer.c \
$(COMMON_SRC) $(COMMON_SRC)
# Source files for the FY90Q target # Source files for the FY90Q target
@ -94,14 +94,14 @@ FY90Q_SRC = drv_adc_fy90q.c \
$(COMMON_SRC) $(COMMON_SRC)
# Source files for the OLIMEXINO target # Source files for the OLIMEXINO target
OLIMEXINO_SRC = drv_spi.c \ OLIMEXINO_SRC = drivers/bus/drv_spi.c \
drv_adc.c \ drivers/adc/drv_adc.c \
drv_adxl345.c \ drivers/accgyro/drv_adxl345.c \
drv_mpu3050.c \ drivers/accgyro/drv_mpu3050.c \
drv_mpu6050.c \ drivers/accgyro/drv_mpu6050.c \
drv_l3g4200d.c \ drivers/accgyro/drv_l3g4200d.c \
drv_pwm.c \ drv_pwm.c \
drv_timer.c \ drivers/timer/drv_timer.c \
$(COMMON_SRC) $(COMMON_SRC)
# In some cases, %.s regarded as intermediate file, which is actually not. # In some cases, %.s regarded as intermediate file, which is actually not.
@ -212,6 +212,7 @@ $(OBJECT_DIR)/$(TARGET)/%.o): %.S
clean: clean:
rm -f $(TARGET_HEX) $(TARGET_ELF) $(TARGET_OBJS) $(TARGET_MAP) rm -f $(TARGET_HEX) $(TARGET_ELF) $(TARGET_OBJS) $(TARGET_MAP)
rm -rf $(OBJECT_DIR)/$(TARGET)
flash_$(TARGET): $(TARGET_HEX) flash_$(TARGET): $(TARGET_HEX)
stty -F $(SERIAL_DEVICE) raw speed 115200 -crtscts cs8 -parenb -cstopb -ixon stty -F $(SERIAL_DEVICE) raw speed 115200 -crtscts cs8 -parenb -cstopb -ixon

File diff suppressed because it is too large Load diff

File diff suppressed because it is too large Load diff

View file

@ -21,7 +21,7 @@
#endif #endif
#include "drv_system.h" // timers, delays, etc #include "drv_system.h" // timers, delays, etc
#include "drv_gpio.h" #include "drivers/gpio/drv_gpio.h"
#ifndef M_PI #ifndef M_PI
#define M_PI 3.14159265358979323846f #define M_PI 3.14159265358979323846f
@ -278,48 +278,48 @@ typedef struct baro_t
#ifdef FY90Q #ifdef FY90Q
// FY90Q // FY90Q
#include "drv_adc.h" #include "drivers/adc/drv_adc.h"
#include "drv_i2c.h" #include "drv_i2c.h"
#include "drv_pwm.h" #include "drv_pwm.h"
#include "drv_uart.h" #include "drivers/serial/drv_uart.h"
#else #else
#ifdef OLIMEXINO #ifdef OLIMEXINO
// OLIMEXINO // OLIMEXINO
#include "drv_adc.h" #include "drivers/adc/drv_adc.h"
#include "drv_i2c.h" #include "drivers/bus/drv_i2c.h"
#include "drv_spi.h" #include "drivers/bus/drv_spi.h"
#include "drv_adxl345.h" #include "drivers/accgyro/drv_adxl345.h"
#include "drv_mpu3050.h" #include "drivers/accgyro/drv_mpu3050.h"
#include "drv_mpu6050.h" #include "drivers/accgyro/drv_mpu6050.h"
#include "drv_l3g4200d.h" #include "drivers/accgyro/drv_l3g4200d.h"
#include "drv_pwm.h" #include "drv_pwm.h"
#include "drv_timer.h" #include "drivers/timer/drv_timer.h"
#include "drv_serial.h" #include "drivers/serial/drv_serial.h"
#include "drv_uart.h" #include "drivers/serial/drv_uart.h"
#include "drv_softserial.h" #include "drivers/serial/drv_softserial.h"
#else #else
// AfroFlight32 // AfroFlight32
#include "drv_adc.h" #include "drivers/adc/drv_adc.h"
#include "drv_adxl345.h" #include "drivers/accgyro/drv_adxl345.h"
#include "drv_bma280.h" #include "drivers/accgyro/drv_bma280.h"
#include "drv_bmp085.h" #include "drivers/altimeter/drv_bmp085.h"
#include "drv_ms5611.h" #include "drivers/altimeter/drv_ms5611.h"
#include "drv_hmc5883l.h" #include "drivers/compass/drv_hmc5883l.h"
#include "drv_i2c.h" #include "drivers/bus/drv_i2c.h"
#include "drv_spi.h" #include "drivers/bus/drv_spi.h"
#include "drv_ledring.h" #include "drivers/light/drv_ledring.h"
#include "drv_mma845x.h" #include "drivers/accgyro/drv_mma845x.h"
#include "drv_mpu3050.h" #include "drivers/accgyro/drv_mpu3050.h"
#include "drv_mpu6050.h" #include "drivers/accgyro/drv_mpu6050.h"
#include "drv_l3g4200d.h" #include "drivers/accgyro/drv_l3g4200d.h"
#include "drv_pwm.h" #include "drv_pwm.h"
#include "drv_timer.h" #include "drivers/timer/drv_timer.h"
#include "drv_serial.h" #include "drivers/serial/drv_serial.h"
#include "drv_uart.h" #include "drivers/serial/drv_uart.h"
#include "drv_softserial.h" #include "drivers/serial/drv_softserial.h"
#include "drv_hcsr04.h" #include "drivers/sonar/drv_hcsr04.h"
#endif #endif
#endif #endif

View file

@ -1,7 +1,7 @@
#include "board.h" #include "board.h"
#include "mw.h" #include "mw.h"
#include "telemetry_common.h" #include "telemetry/telemetry_common.h"
core_t core; core_t core;

View file

@ -1,8 +1,8 @@
#include "board.h" #include "board.h"
#include "mw.h" #include "mw.h"
#include "cli.h" #include "ui/cli.h"
#include "telemetry_common.h" #include "telemetry/telemetry_common.h"
// June 2013 V2.2-dev // June 2013 V2.2-dev

View file

@ -1,8 +1,8 @@
#include "board.h" #include "board.h"
#include "mw.h" #include "mw.h"
#include "cli.h" #include "ui/cli.h"
#include "telemetry_common.h" #include "telemetry/telemetry_common.h"
// Multiwii Serial Protocol 0 // Multiwii Serial Protocol 0
#define MSP_VERSION 0 #define MSP_VERSION 0