1
0
Fork 0
mirror of https://github.com/iNavFlight/inav.git synced 2025-07-24 00:35:34 +03:00

Moved accgyro, barometer and compass drivers into subdirectories

This commit is contained in:
Martin Budden 2017-04-25 09:47:37 +01:00
parent 38c1bb6bf5
commit 5874f92f87
186 changed files with 725 additions and 725 deletions

View file

@ -660,7 +660,7 @@ STM32F30x_COMMON_SRC = \
STM32F4xx_COMMON_SRC = \ STM32F4xx_COMMON_SRC = \
startup_stm32f40xx.s \ startup_stm32f40xx.s \
target/system_stm32f4xx.c \ target/system_stm32f4xx.c \
drivers/accgyro_mpu.c \ drivers/accgyro/accgyro_mpu.c \
drivers/adc_stm32f4xx.c \ drivers/adc_stm32f4xx.c \
drivers/adc_stm32f4xx.c \ drivers/adc_stm32f4xx.c \
drivers/bus_i2c_stm32f10x.c \ drivers/bus_i2c_stm32f10x.c \
@ -675,7 +675,7 @@ STM32F4xx_COMMON_SRC = \
STM32F7xx_COMMON_SRC = \ STM32F7xx_COMMON_SRC = \
startup_stm32f745xx.s \ startup_stm32f745xx.s \
target/system_stm32f7xx.c \ target/system_stm32f7xx.c \
drivers/accgyro_mpu.c \ drivers/accgyro/accgyro_mpu.c \
drivers/adc_stm32f7xx.c \ drivers/adc_stm32f7xx.c \
drivers/bus_i2c_hal.c \ drivers/bus_i2c_hal.c \
drivers/dma_stm32f7xx.c \ drivers/dma_stm32f7xx.c \

View file

@ -39,8 +39,8 @@
#include "config/parameter_group.h" #include "config/parameter_group.h"
#include "config/parameter_group_ids.h" #include "config/parameter_group_ids.h"
#include "drivers/accgyro.h" #include "drivers/accgyro/accgyro.h"
#include "drivers/compass.h" #include "drivers/compass/compass.h"
#include "drivers/light_led.h" #include "drivers/light_led.h"
#include "drivers/pwm_rx.h" #include "drivers/pwm_rx.h"
#include "drivers/sensor.h" #include "drivers/sensor.h"

View file

@ -40,10 +40,10 @@
#include "drivers/sensor.h" #include "drivers/sensor.h"
#include "drivers/time.h" #include "drivers/time.h"
#include "drivers/serial.h" #include "drivers/serial.h"
#include "drivers/compass.h" #include "drivers/compass/compass.h"
#include "drivers/timer.h" #include "drivers/timer.h"
#include "drivers/pwm_rx.h" #include "drivers/pwm_rx.h"
#include "drivers/accgyro.h" #include "drivers/accgyro/accgyro.h"
#include "drivers/light_led.h" #include "drivers/light_led.h"
#include "drivers/gyro_sync.h" #include "drivers/gyro_sync.h"

View file

@ -20,7 +20,7 @@
#include "common/axis.h" #include "common/axis.h"
#include "drivers/exti.h" #include "drivers/exti.h"
#include "drivers/sensor.h" #include "drivers/sensor.h"
#include "drivers/accgyro_mpu.h" #include "drivers/accgyro/accgyro_mpu.h"
#ifndef MPU_I2C_INSTANCE #ifndef MPU_I2C_INSTANCE
#define MPU_I2C_INSTANCE I2C_DEVICE #define MPU_I2C_INSTANCE I2C_DEVICE

View file

@ -20,12 +20,12 @@
#include <platform.h> #include <platform.h>
#include "system.h" #include "drivers/system.h"
#include "bus_i2c.h" #include "drivers/bus_i2c.h"
#include "sensor.h" #include "drivers/sensor.h"
#include "accgyro.h" #include "drivers/accgyro/accgyro.h"
#include "accgyro_adxl345.h" #include "drivers/accgyro/accgyro_adxl345.h"
// ADXL345, Alternative address mode 0x53 // ADXL345, Alternative address mode 0x53
#define ADXL345_ADDRESS 0x53 #define ADXL345_ADDRESS 0x53

View file

@ -20,11 +20,11 @@
#include <platform.h> #include <platform.h>
#include "bus_i2c.h" #include "drivers/bus_i2c.h"
#include "sensor.h" #include "drivers/sensor.h"
#include "accgyro.h" #include "drivers/accgyro/accgyro.h"
#include "accgyro_bma280.h" #include "drivers/accgyro/accgyro_bma280.h"
// BMA280, default I2C address mode 0x18 // BMA280, default I2C address mode 0x18
#define BMA280_ADDRESS 0x18 #define BMA280_ADDRESS 0x18

View file

@ -23,8 +23,8 @@
#include "common/axis.h" #include "common/axis.h"
#include "common/utils.h" #include "common/utils.h"
#include "accgyro.h" #include "drivers/accgyro/accgyro.h"
#include "accgyro_fake.h" #include "drivers/accgyro/accgyro_fake.h"
#ifdef USE_FAKE_GYRO #ifdef USE_FAKE_GYRO

View file

@ -17,7 +17,7 @@
#pragma once #pragma once
#include "accgyro.h" #include "drivers/accgyro/accgyro.h"
bool fakeAccDetect(accDev_t *acc); bool fakeAccDetect(accDev_t *acc);
void fakeAccSet(int16_t x, int16_t y, int16_t z); void fakeAccSet(int16_t x, int16_t y, int16_t z);

View file

@ -20,16 +20,16 @@
#include <platform.h> #include <platform.h>
#include "system.h" #include "drivers/system.h"
#include "time.h" #include "drivers/time.h"
#include "bus_i2c.h" #include "drivers/bus_i2c.h"
#include "common/maths.h" #include "common/maths.h"
#include "common/axis.h" #include "common/axis.h"
#include "sensor.h" #include "drivers/sensor.h"
#include "accgyro.h" #include "drivers/accgyro/accgyro.h"
#include "accgyro_l3g4200d.h" #include "drivers/accgyro/accgyro_l3g4200d.h"
// L3G4200D, Standard address 0x68 // L3G4200D, Standard address 0x68
#define L3G4200D_ADDRESS 0x68 #define L3G4200D_ADDRESS 0x68

View file

@ -24,13 +24,13 @@
#include "common/maths.h" #include "common/maths.h"
#include "time.h" #include "drivers/time.h"
#include "io.h" #include "drivers/io.h"
#include "bus_spi.h" #include "drivers/bus_spi.h"
#include "sensor.h" #include "drivers/sensor.h"
#include "accgyro.h" #include "drivers/accgyro/accgyro.h"
#include "accgyro_l3gd20.h" #include "drivers/accgyro/accgyro_l3gd20.h"
#define READ_CMD ((uint8_t)0x80) #define READ_CMD ((uint8_t)0x80)
#define MULTIPLEBYTE_CMD ((uint8_t)0x40) #define MULTIPLEBYTE_CMD ((uint8_t)0x40)

View file

@ -27,13 +27,13 @@
#include "common/maths.h" #include "common/maths.h"
#include "common/axis.h" #include "common/axis.h"
#include "time.h" #include "drivers/time.h"
#include "io.h" #include "drivers/io.h"
#include "bus_i2c.h" #include "drivers/bus_i2c.h"
#include "sensor.h" #include "drivers/sensor.h"
#include "accgyro.h" #include "drivers/accgyro/accgyro.h"
#include "accgyro_lsm303dlhc.h" #include "drivers/accgyro/accgyro_lsm303dlhc.h"
// Addresses (7 bit address format) // Addresses (7 bit address format)

View file

@ -20,13 +20,13 @@
#include "platform.h" #include "platform.h"
#include "time.h" #include "drivers/time.h"
#include "io.h" #include "drivers/io.h"
#include "bus_i2c.h" #include "drivers/bus_i2c.h"
#include "sensor.h" #include "drivers/sensor.h"
#include "accgyro.h" #include "drivers/accgyro/accgyro.h"
#include "accgyro_mma845x.h" #include "drivers/accgyro/accgyro_mma845x.h"
#ifndef MMA8452_I2C_INSTANCE #ifndef MMA8452_I2C_INSTANCE
#define MMA8452_I2C_INSTANCE I2CDEV_1 #define MMA8452_I2C_INSTANCE I2CDEV_1

View file

@ -28,23 +28,23 @@
#include "common/maths.h" #include "common/maths.h"
#include "nvic.h" #include "drivers/nvic.h"
#include "system.h" #include "drivers/system.h"
#include "time.h" #include "drivers/time.h"
#include "io.h" #include "drivers/io.h"
#include "exti.h" #include "drivers/exti.h"
#include "bus_i2c.h" #include "drivers/bus_i2c.h"
#include "sensor.h" #include "drivers/sensor.h"
#include "accgyro.h" #include "drivers/accgyro/accgyro.h"
#include "accgyro_mpu3050.h" #include "drivers/accgyro/accgyro_mpu3050.h"
#include "accgyro_mpu6050.h" #include "drivers/accgyro/accgyro_mpu6050.h"
#include "accgyro_mpu6500.h" #include "drivers/accgyro/accgyro_mpu6500.h"
#include "accgyro_spi_mpu6000.h" #include "drivers/accgyro/accgyro_spi_mpu6000.h"
#include "accgyro_spi_mpu6500.h" #include "drivers/accgyro/accgyro_spi_mpu6500.h"
#include "accgyro_spi_mpu9250.h" #include "drivers/accgyro/accgyro_spi_mpu9250.h"
#include "accgyro_mpu.h" #include "drivers/accgyro/accgyro_mpu.h"
//#define DEBUG_MPU_DATA_READY_INTERRUPT //#define DEBUG_MPU_DATA_READY_INTERRUPT

View file

@ -17,8 +17,8 @@
#pragma once #pragma once
#include "exti.h" #include "drivers/exti.h"
#include "sensor.h" #include "drivers/sensor.h"
//#define DEBUG_MPU_DATA_READY_INTERRUPT //#define DEBUG_MPU_DATA_READY_INTERRUPT

View file

@ -22,15 +22,15 @@
#include "common/maths.h" #include "common/maths.h"
#include "system.h" #include "drivers/system.h"
#include "time.h" #include "drivers/time.h"
#include "exti.h" #include "drivers/exti.h"
#include "bus_i2c.h" #include "drivers/bus_i2c.h"
#include "sensor.h" #include "drivers/sensor.h"
#include "accgyro.h" #include "drivers/accgyro/accgyro.h"
#include "accgyro_mpu.h" #include "drivers/accgyro/accgyro_mpu.h"
#include "accgyro_mpu3050.h" #include "drivers/accgyro/accgyro_mpu3050.h"
// MPU3050, Standard address 0x68 // MPU3050, Standard address 0x68
#define MPU3050_ADDRESS 0x68 #define MPU3050_ADDRESS 0x68

View file

@ -26,18 +26,18 @@
#include "common/maths.h" #include "common/maths.h"
#include "common/utils.h" #include "common/utils.h"
#include "nvic.h" #include "drivers/nvic.h"
#include "time.h" #include "drivers/time.h"
#include "gpio.h" #include "drivers/gpio.h"
#include "exti.h" #include "drivers/exti.h"
#include "bus_i2c.h" #include "drivers/bus_i2c.h"
#include "gyro_sync.h" #include "drivers/gyro_sync.h"
#include "sensor.h" #include "drivers/sensor.h"
#include "accgyro.h" #include "drivers/accgyro/accgyro.h"
#include "accgyro_mpu.h" #include "drivers/accgyro/accgyro_mpu.h"
#include "accgyro_mpu6050.h" #include "drivers/accgyro/accgyro_mpu6050.h"
//#define DEBUG_MPU_DATA_READY_INTERRUPT //#define DEBUG_MPU_DATA_READY_INTERRUPT

View file

@ -24,16 +24,16 @@
#include "common/axis.h" #include "common/axis.h"
#include "common/maths.h" #include "common/maths.h"
#include "system.h" #include "drivers/system.h"
#include "time.h" #include "drivers/time.h"
#include "exti.h" #include "drivers/exti.h"
#include "gpio.h" #include "drivers/gpio.h"
#include "gyro_sync.h" #include "drivers/gyro_sync.h"
#include "sensor.h" #include "drivers/sensor.h"
#include "accgyro.h" #include "drivers/accgyro/accgyro.h"
#include "accgyro_mpu.h" #include "drivers/accgyro/accgyro_mpu.h"
#include "accgyro_mpu6500.h" #include "drivers/accgyro/accgyro_mpu6500.h"
void mpu6500AccInit(accDev_t *acc) void mpu6500AccInit(accDev_t *acc)
{ {

View file

@ -30,21 +30,21 @@
#include "common/axis.h" #include "common/axis.h"
#include "common/maths.h" #include "common/maths.h"
#include "system.h" #include "drivers/system.h"
#include "time.h" #include "drivers/time.h"
#include "io.h" #include "drivers/io.h"
#include "exti.h" #include "drivers/exti.h"
#include "bus_spi.h" #include "drivers/bus_spi.h"
#include "gyro_sync.h" #include "drivers/gyro_sync.h"
#include "sensor.h" #include "drivers/sensor.h"
#include "accgyro.h" #include "drivers/accgyro/accgyro.h"
#include "accgyro_mpu.h" #include "drivers/accgyro/accgyro_mpu.h"
#if defined(USE_GYRO_SPI_MPU6000) || defined(USE_ACC_SPI_MPU6000) #if defined(USE_GYRO_SPI_MPU6000) || defined(USE_ACC_SPI_MPU6000)
#include "accgyro_spi_mpu6000.h" #include "drivers/accgyro/accgyro_spi_mpu6000.h"
static void mpu6000AccAndGyroInit(gyroDev_t *gyro); static void mpu6000AccAndGyroInit(gyroDev_t *gyro);

View file

@ -1,7 +1,7 @@
#pragma once #pragma once
#include "sensor.h" #include "drivers/sensor.h"
#define MPU6000_CONFIG 0x1A #define MPU6000_CONFIG 0x1A

View file

@ -25,17 +25,17 @@
#include "common/axis.h" #include "common/axis.h"
#include "common/maths.h" #include "common/maths.h"
#include "system.h" #include "drivers/system.h"
#include "time.h" #include "drivers/time.h"
#include "exti.h" #include "drivers/exti.h"
#include "io.h" #include "drivers/io.h"
#include "bus_spi.h" #include "drivers/bus_spi.h"
#include "sensor.h" #include "drivers/sensor.h"
#include "accgyro.h" #include "drivers/accgyro/accgyro.h"
#include "accgyro_mpu.h" #include "drivers/accgyro/accgyro_mpu.h"
#include "accgyro_mpu6500.h" #include "drivers/accgyro/accgyro_mpu6500.h"
#include "accgyro_spi_mpu6500.h" #include "drivers/accgyro/accgyro_spi_mpu6500.h"
#define DISABLE_MPU6500(spiCsnPin) IOHi(spiCsnPin) #define DISABLE_MPU6500(spiCsnPin) IOHi(spiCsnPin)
#define ENABLE_MPU6500(spiCsnPin) IOLo(spiCsnPin) #define ENABLE_MPU6500(spiCsnPin) IOLo(spiCsnPin)

View file

@ -17,7 +17,7 @@
#pragma once #pragma once
#include "sensor.h" #include "drivers/sensor.h"
uint8_t mpu6500SpiDetect(const busDevice_t *bus); uint8_t mpu6500SpiDetect(const busDevice_t *bus);

View file

@ -33,19 +33,19 @@
#include "common/axis.h" #include "common/axis.h"
#include "common/maths.h" #include "common/maths.h"
#include "io.h" #include "drivers/io.h"
#include "system.h" #include "drivers/system.h"
#include "time.h" #include "drivers/time.h"
#include "exti.h" #include "drivers/exti.h"
#include "bus_spi.h" #include "drivers/bus_spi.h"
#include "gyro_sync.h" #include "drivers/gyro_sync.h"
#include "light_led.h" #include "drivers/light_led.h"
#include "sensor.h" #include "drivers/sensor.h"
#include "accgyro.h" #include "drivers/accgyro/accgyro.h"
#include "accgyro_mpu.h" #include "drivers/accgyro/accgyro_mpu.h"
#include "accgyro_spi_mpu9250.h" #include "drivers/accgyro/accgyro_spi_mpu9250.h"
static bool mpuSpi9250InitDone = false; static bool mpuSpi9250InitDone = false;

View file

@ -1,7 +1,7 @@
#pragma once #pragma once
#include "sensor.h" #include "drivers/sensor.h"
#define mpu9250_CONFIG 0x1A #define mpu9250_CONFIG 0x1A

View file

@ -23,7 +23,7 @@
#include "build/build_config.h" #include "build/build_config.h"
#include "build/debug.h" #include "build/debug.h"
#include "time.h" #include "drivers/time.h"
#include "adc.h" #include "adc.h"
#include "adc_impl.h" #include "adc_impl.h"

View file

@ -17,7 +17,7 @@
#pragma once #pragma once
#include "io_types.h" #include "drivers/io_types.h"
typedef enum { typedef enum {
ADC_BATTERY = 0, ADC_BATTERY = 0,

View file

@ -17,7 +17,7 @@
#pragma once #pragma once
#include "io_types.h" #include "drivers/io_types.h"
#include "rcc_types.h" #include "rcc_types.h"
#if defined(STM32F4) || defined(STM32F7) #if defined(STM32F4) || defined(STM32F7)

View file

@ -25,12 +25,12 @@
#include "build/build_config.h" #include "build/build_config.h"
#include "time.h" #include "drivers/time.h"
#include "sensor.h" #include "drivers/sensor.h"
#include "accgyro.h" #include "drivers/accgyro/accgyro.h"
#include "adc.h" #include "adc.h"
#include "adc_impl.h" #include "adc_impl.h"
#include "io.h" #include "drivers/io.h"
#include "rcc.h" #include "rcc.h"
#ifndef ADC_INSTANCE #ifndef ADC_INSTANCE

View file

@ -20,15 +20,15 @@
#include <string.h> #include <string.h>
#include "platform.h" #include "platform.h"
#include "time.h" #include "drivers/time.h"
#include "gpio.h" #include "drivers/gpio.h"
#include "sensor.h" #include "drivers/sensor.h"
#include "accgyro.h" #include "drivers/accgyro/accgyro.h"
#include "adc.h" #include "adc.h"
#include "adc_impl.h" #include "adc_impl.h"
#include "io.h" #include "drivers/io.h"
#include "rcc.h" #include "rcc.h"
#include "common/utils.h" #include "common/utils.h"

View file

@ -20,14 +20,14 @@
#include <string.h> #include <string.h>
#include "platform.h" #include "platform.h"
#include "time.h" #include "drivers/time.h"
#include "io.h" #include "drivers/io.h"
#include "io_impl.h" #include "io_impl.h"
#include "rcc.h" #include "rcc.h"
#include "sensor.h" #include "drivers/sensor.h"
#include "accgyro.h" #include "drivers/accgyro/accgyro.h"
#include "adc.h" #include "adc.h"
#include "adc_impl.h" #include "adc_impl.h"

View file

@ -20,15 +20,15 @@
#include <string.h> #include <string.h>
#include "platform.h" #include "platform.h"
#include "time.h" #include "drivers/time.h"
#include "io.h" #include "drivers/io.h"
#include "io_impl.h" #include "io_impl.h"
#include "rcc.h" #include "rcc.h"
#include "dma.h" #include "dma.h"
#include "sensor.h" #include "drivers/sensor.h"
#include "accgyro.h" #include "drivers/accgyro/accgyro.h"
#include "adc.h" #include "adc.h"
#include "adc_impl.h" #include "adc_impl.h"

View file

@ -22,16 +22,16 @@
#include "build/build_config.h" #include "build/build_config.h"
#include "barometer.h" #include "drivers/barometer/barometer.h"
#include "gpio.h" #include "drivers/gpio.h"
#include "time.h" #include "drivers/time.h"
#include "bus_i2c.h" #include "drivers/bus_i2c.h"
#include "nvic.h" #include "drivers/nvic.h"
#include "exti.h" #include "drivers/exti.h"
#include "io.h" #include "drivers/io.h"
#include "barometer_bmp085.h" #include "drivers/barometer/barometer_bmp085.h"
#ifdef BARO #ifdef BARO

View file

@ -17,7 +17,7 @@
#pragma once #pragma once
#include "io_types.h" #include "drivers/io_types.h"
typedef struct bmp085Config_s { typedef struct bmp085Config_s {
ioTag_t xclrIO; ioTag_t xclrIO;

View file

@ -22,13 +22,13 @@
#include "build/build_config.h" #include "build/build_config.h"
#include "barometer.h" #include "drivers/barometer/barometer.h"
#include "time.h" #include "drivers/time.h"
#include "bus_i2c.h" #include "drivers/bus_i2c.h"
#include "barometer_bmp280.h" #include "drivers/barometer/barometer_bmp280.h"
#include "barometer_spi_bmp280.h" #include "drivers/barometer/barometer_spi_bmp280.h"
#ifdef BARO #ifdef BARO

View file

@ -22,8 +22,8 @@
#ifdef USE_FAKE_BARO #ifdef USE_FAKE_BARO
#include "barometer.h" #include "drivers/barometer/barometer.h"
#include "barometer_fake.h" #include "drivers/barometer/barometer_fake.h"
static int32_t fakePressure; static int32_t fakePressure;

View file

@ -23,12 +23,12 @@
#include "build/build_config.h" #include "build/build_config.h"
#include "common/utils.h" #include "common/utils.h"
#include "barometer.h" #include "drivers/barometer/barometer.h"
#include "barometer_ms56xx.h" #include "drivers/barometer/barometer_ms56xx.h"
#include "barometer_spi_ms56xx.h" #include "drivers/barometer/barometer_spi_ms56xx.h"
#include "time.h" #include "drivers/time.h"
#include "bus_i2c.h" #include "drivers/bus_i2c.h"
// MS56xx, Standard address 0x77 // MS56xx, Standard address 0x77
#define MS56XX_ADDR 0x77 #define MS56XX_ADDR 0x77

View file

@ -20,11 +20,11 @@
#include <platform.h> #include <platform.h>
#include "io.h" #include "drivers/io.h"
#include "bus_spi.h" #include "drivers/bus_spi.h"
#include "barometer.h" #include "drivers/barometer/barometer.h"
#include "barometer_bmp280.h" #include "drivers/barometer/barometer_bmp280.h"
#ifdef USE_BARO_SPI_BMP280 #ifdef USE_BARO_SPI_BMP280
#define DISABLE_BMP280 IOHi(bmp280CsPin) #define DISABLE_BMP280 IOHi(bmp280CsPin)

View file

@ -20,11 +20,11 @@
#include <platform.h> #include <platform.h>
#include "io.h" #include "drivers/io.h"
#include "bus_spi.h" #include "drivers/bus_spi.h"
#include "barometer.h" #include "drivers/barometer/barometer.h"
#include "barometer_ms56xx.h" #include "drivers/barometer/barometer_ms56xx.h"
#if defined(USE_BARO_SPI_MS5611) || defined(USE_BARO_SPI_MS5607) #if defined(USE_BARO_SPI_MS5611) || defined(USE_BARO_SPI_MS5607)

View file

@ -20,11 +20,11 @@
#include <platform.h> #include <platform.h>
#include "io.h" #include "drivers/io.h"
#include "time.h" #include "drivers/time.h"
#include "bus_i2c.h" #include "drivers/bus_i2c.h"
#include "nvic.h" #include "drivers/nvic.h"
#include "io_impl.h" #include "io_impl.h"
#include "rcc.h" #include "rcc.h"

View file

@ -22,8 +22,8 @@
#include "build/build_config.h" #include "build/build_config.h"
#include "bus_i2c.h" #include "drivers/bus_i2c.h"
#include "io.h" #include "drivers/io.h"
// Software I2C driver, using same pins as hardware I2C, with hw i2c module disabled. // Software I2C driver, using same pins as hardware I2C, with hw i2c module disabled.
// Can be configured for I2C2 pinout (SCL: PB10, SDA: PB11) or I2C1 pinout (SCL: PB6, SDA: PB7) // Can be configured for I2C2 pinout (SCL: PB10, SDA: PB11) or I2C1 pinout (SCL: PB6, SDA: PB7)

View file

@ -23,14 +23,14 @@
#include "build/atomic.h" #include "build/atomic.h"
#include "io.h" #include "drivers/io.h"
#include "time.h" #include "drivers/time.h"
#include "bus_i2c.h" #include "drivers/bus_i2c.h"
#include "nvic.h" #include "drivers/nvic.h"
#include "io_impl.h" #include "io_impl.h"
#include "rcc.h" #include "rcc.h"
#include "light_led.h" #include "drivers/light_led.h"
#ifndef SOFT_I2C #ifndef SOFT_I2C

View file

@ -20,12 +20,12 @@
#include <platform.h> #include <platform.h>
#include "time.h" #include "drivers/time.h"
#include "io.h" #include "drivers/io.h"
#include "io_impl.h" #include "io_impl.h"
#include "rcc.h" #include "rcc.h"
#include "bus_i2c.h" #include "drivers/bus_i2c.h"
#ifndef SOFT_I2C #ifndef SOFT_I2C

View file

@ -20,9 +20,9 @@
#include <platform.h> #include <platform.h>
#include "bus_spi.h" #include "drivers/bus_spi.h"
#include "exti.h" #include "drivers/exti.h"
#include "io.h" #include "drivers/io.h"
#include "io_impl.h" #include "io_impl.h"
#include "rcc.h" #include "rcc.h"

View file

@ -17,7 +17,7 @@
#pragma once #pragma once
#include "io_types.h" #include "drivers/io_types.h"
#include "rcc_types.h" #include "rcc_types.h"
#if defined(STM32F4) || defined(STM32F3) #if defined(STM32F4) || defined(STM32F3)

View file

@ -20,11 +20,11 @@
#include <platform.h> #include <platform.h>
#include "bus_spi.h" #include "drivers/bus_spi.h"
#include "dma.h" #include "dma.h"
#include "io.h" #include "drivers/io.h"
#include "io_impl.h" #include "io_impl.h"
#include "nvic.h" #include "drivers/nvic.h"
#include "rcc.h" #include "rcc.h"
#ifndef SPI1_SCK_PIN #ifndef SPI1_SCK_PIN

View file

@ -25,9 +25,9 @@
#include "build/build_config.h" #include "build/build_config.h"
#include "io.h" #include "drivers/io.h"
#include "io_impl.h" #include "io_impl.h"
#include "bus_spi.h" #include "drivers/bus_spi.h"
#include "bus_spi_soft.h" #include "bus_spi_soft.h"

View file

@ -17,7 +17,7 @@
#pragma once #pragma once
#include "io_types.h" #include "drivers/io_types.h"
typedef enum softSPIDevice { typedef enum softSPIDevice {
SOFT_SPIDEV_1 = 0, SOFT_SPIDEV_1 = 0,

View file

@ -17,7 +17,7 @@
#pragma once #pragma once
#include "sensor.h" #include "drivers/sensor.h"
typedef struct magDev_s { typedef struct magDev_s {
sensorMagInitFuncPtr init; // initialize function sensorMagInitFuncPtr init; // initialize function

View file

@ -31,19 +31,19 @@
#include "common/maths.h" #include "common/maths.h"
#include "common/utils.h" #include "common/utils.h"
#include "time.h" #include "drivers/time.h"
#include "io.h" #include "drivers/io.h"
#include "bus_i2c.h" #include "drivers/bus_i2c.h"
#include "bus_spi.h" #include "drivers/bus_spi.h"
#include "sensor.h" #include "drivers/sensor.h"
#include "compass.h" #include "drivers/compass/compass.h"
#include "accgyro.h" #include "drivers/accgyro/accgyro.h"
#include "accgyro_mpu.h" #include "drivers/accgyro/accgyro_mpu.h"
#include "accgyro_mpu6500.h" #include "drivers/accgyro/accgyro_mpu6500.h"
#include "accgyro_spi_mpu6500.h" #include "drivers/accgyro/accgyro_spi_mpu6500.h"
#include "compass_ak8963.h" #include "drivers/compass/compass_ak8963.h"
// This sensor is available in MPU-9250. // This sensor is available in MPU-9250.

View file

@ -30,14 +30,14 @@
#include "common/maths.h" #include "common/maths.h"
#include "common/utils.h" #include "common/utils.h"
#include "time.h" #include "drivers/time.h"
#include "gpio.h" #include "drivers/gpio.h"
#include "bus_i2c.h" #include "drivers/bus_i2c.h"
#include "sensor.h" #include "drivers/sensor.h"
#include "compass.h" #include "drivers/compass/compass.h"
#include "compass_ak8975.h" #include "drivers/compass/compass_ak8975.h"
// This sensor is available in MPU-9150. // This sensor is available in MPU-9150.

View file

@ -27,8 +27,8 @@
#include "common/axis.h" #include "common/axis.h"
#include "common/utils.h" #include "common/utils.h"
#include "compass.h" #include "drivers/compass/compass.h"
#include "compass_fake.h" #include "drivers/compass/compass_fake.h"
static int16_t fakeMagData[XYZ_AXIS_COUNT]; static int16_t fakeMagData[XYZ_AXIS_COUNT];

View file

@ -29,19 +29,19 @@
#include "common/axis.h" #include "common/axis.h"
#include "common/maths.h" #include "common/maths.h"
#include "time.h" #include "drivers/time.h"
#include "nvic.h" #include "drivers/nvic.h"
#include "io.h" #include "drivers/io.h"
#include "exti.h" #include "drivers/exti.h"
#include "bus_i2c.h" #include "drivers/bus_i2c.h"
#include "light_led.h" #include "drivers/light_led.h"
#include "logging.h" #include "drivers/logging.h"
#include "sensor.h" #include "drivers/sensor.h"
#include "compass.h" #include "drivers/compass/compass.h"
#include "compass_hmc5883l.h" #include "drivers/compass/compass_hmc5883l.h"
//#define DEBUG_MAG_DATA_READY_INTERRUPT //#define DEBUG_MAG_DATA_READY_INTERRUPT

View file

@ -17,7 +17,7 @@
#pragma once #pragma once
#include "io_types.h" #include "drivers/io_types.h"
typedef struct hmc5883Config_s { typedef struct hmc5883Config_s {
ioTag_t intTag; ioTag_t intTag;

View file

@ -29,17 +29,17 @@
#include "common/axis.h" #include "common/axis.h"
#include "common/maths.h" #include "common/maths.h"
#include "time.h" #include "drivers/time.h"
#include "nvic.h" #include "drivers/nvic.h"
#include "io.h" #include "drivers/io.h"
#include "exti.h" #include "drivers/exti.h"
#include "bus_i2c.h" #include "drivers/bus_i2c.h"
#include "light_led.h" #include "drivers/light_led.h"
#include "sensor.h" #include "drivers/sensor.h"
#include "compass.h" #include "drivers/compass/compass.h"
#include "compass_ist8310.h" #include "drivers/compass/compass_ist8310.h"
/* ist8310 Slave Address Select : default address 0x0C /* ist8310 Slave Address Select : default address 0x0C
* CAD1 | CAD0 | Address * CAD1 | CAD0 | Address

View file

@ -30,17 +30,17 @@
#include "common/maths.h" #include "common/maths.h"
#include "common/utils.h" #include "common/utils.h"
#include "time.h" #include "drivers/time.h"
#include "gpio.h" #include "drivers/gpio.h"
#include "bus_i2c.h" #include "drivers/bus_i2c.h"
#include "sensors/boardalignment.h" #include "sensors/boardalignment.h"
#include "sensors/sensors.h" #include "sensors/sensors.h"
#include "sensor.h" #include "drivers/sensor.h"
#include "compass.h" #include "drivers/compass/compass.h"
#include "compass_mag3110.h" #include "drivers/compass/compass_mag3110.h"
#define MAG3110_MAG_I2C_ADDRESS 0x0E #define MAG3110_MAG_I2C_ADDRESS 0x0E

View file

@ -20,8 +20,8 @@
#include "platform.h" #include "platform.h"
#include "bus_i2c.h" #include "drivers/bus_i2c.h"
#include "time.h" #include "drivers/time.h"
#include "display_ug2864hsweg01.h" #include "display_ug2864hsweg01.h"

View file

@ -21,7 +21,7 @@
#include <platform.h> #include <platform.h>
#include "nvic.h" #include "drivers/nvic.h"
#include "dma.h" #include "dma.h"
/* /*

View file

@ -21,7 +21,7 @@
#include <platform.h> #include <platform.h>
#include "nvic.h" #include "drivers/nvic.h"
#include "dma.h" #include "dma.h"
/* /*

View file

@ -5,9 +5,9 @@
#include "platform.h" #include "platform.h"
#include "build/assert.h" #include "build/assert.h"
#include "nvic.h" #include "drivers/nvic.h"
#include "io_impl.h" #include "io_impl.h"
#include "exti.h" #include "drivers/exti.h"
#ifdef USE_EXTI #ifdef USE_EXTI

View file

@ -18,7 +18,7 @@
#pragma once #pragma once
#include "io_types.h" #include "drivers/io_types.h"
// old EXTI interface, to be replaced // old EXTI interface, to be replaced
typedef struct extiConfig_s { typedef struct extiConfig_s {

View file

@ -23,9 +23,9 @@
#ifdef USE_FLASH_M25P16 #ifdef USE_FLASH_M25P16
#include "flash_m25p16.h" #include "flash_m25p16.h"
#include "io.h" #include "drivers/io.h"
#include "bus_spi.h" #include "drivers/bus_spi.h"
#include "time.h" #include "drivers/time.h"
#define M25P16_INSTRUCTION_RDID 0x9F #define M25P16_INSTRUCTION_RDID 0x9F
#define M25P16_INSTRUCTION_READ_BYTES 0x03 #define M25P16_INSTRUCTION_READ_BYTES 0x03

View file

@ -19,7 +19,7 @@
#include <stdint.h> #include <stdint.h>
#include "flash.h" #include "flash.h"
#include "io_types.h" #include "drivers/io_types.h"
#define M25P16_PAGESIZE 256 #define M25P16_PAGESIZE 256

View file

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

View file

@ -20,7 +20,7 @@
#include "platform.h" #include "platform.h"
#include "gpio.h" #include "drivers/gpio.h"
#define MODE_OFFSET 0 #define MODE_OFFSET 0
#define PUPD_OFFSET 2 #define PUPD_OFFSET 2

View file

@ -22,7 +22,7 @@
#include "build/build_config.h" #include "build/build_config.h"
#include "gpio.h" #include "drivers/gpio.h"
#define MODE_OFFSET 0 #define MODE_OFFSET 0
#define PUPD_OFFSET 2 #define PUPD_OFFSET 2

View file

@ -20,7 +20,7 @@
#include "platform.h" #include "platform.h"
#include "gpio.h" #include "drivers/gpio.h"
#define MODE_OFFSET 0 #define MODE_OFFSET 0
#define PUPD_OFFSET 5 #define PUPD_OFFSET 5

View file

@ -25,9 +25,9 @@
#include "gps_i2cnav.h" #include "gps_i2cnav.h"
#include "gpio.h" #include "drivers/gpio.h"
#include "time.h" #include "drivers/time.h"
#include "bus_i2c.h" #include "drivers/bus_i2c.h"
#ifndef GPS_I2C_INSTANCE #ifndef GPS_I2C_INSTANCE
#define GPS_I2C_INSTANCE I2CDEV_1 #define GPS_I2C_INSTANCE I2CDEV_1

View file

@ -20,9 +20,9 @@
#include "platform.h" #include "platform.h"
#include "sensor.h" #include "drivers/sensor.h"
#include "accgyro.h" #include "drivers/accgyro/accgyro.h"
#include "gyro_sync.h" #include "drivers/gyro_sync.h"
bool gyroSyncCheckIntStatus(gyroDev_t *gyro) bool gyroSyncCheckIntStatus(gyroDev_t *gyro)
{ {

View file

@ -15,7 +15,7 @@
* along with Cleanflight. If not, see <http://www.gnu.org/licenses/>. * along with Cleanflight. If not, see <http://www.gnu.org/licenses/>.
*/ */
#include "drivers/accgyro.h" #include "drivers/accgyro/accgyro.h"
bool gyroSyncCheckIntStatus(gyroDev_t *gyro); bool gyroSyncCheckIntStatus(gyroDev_t *gyro);
uint8_t gyroMPU6xxxGetDividerDrops(const gyroDev_t *gyro); uint8_t gyroMPU6xxxGetDividerDrops(const gyroDev_t *gyro);

View file

@ -20,7 +20,7 @@
#include "platform.h" #include "platform.h"
#include "io.h" #include "drivers/io.h"
#include "io_impl.h" #include "io_impl.h"
#include "inverter.h" #include "inverter.h"

View file

@ -2,7 +2,7 @@
#include "common/utils.h" #include "common/utils.h"
#include "io.h" #include "drivers/io.h"
#include "io_impl.h" #include "io_impl.h"
#include "rcc.h" #include "rcc.h"

View file

@ -6,7 +6,7 @@
#include <platform.h> #include <platform.h>
#include "resource.h" #include "resource.h"
#include "io_types.h" #include "drivers/io_types.h"
// preprocessor is used to convert pinid to requested C data value // preprocessor is used to convert pinid to requested C data value
// compile-time error is generated if requested pin is not available (not set in TARGET_IO_PORTx) // compile-time error is generated if requested pin is not available (not set in TARGET_IO_PORTx)

View file

@ -1,7 +1,7 @@
#pragma once #pragma once
// TODO - GPIO_TypeDef include // TODO - GPIO_TypeDef include
#include "io.h" #include "drivers/io.h"
#include "platform.h" #include "platform.h"
typedef struct ioDef_s { typedef struct ioDef_s {

View file

@ -3,9 +3,9 @@
#include <platform.h> #include <platform.h>
#include "gpio.h" #include "drivers/gpio.h"
#include "time.h" #include "drivers/time.h"
#include "bus_i2c.h" #include "drivers/bus_i2c.h"
#include "common/maths.h" #include "common/maths.h"

View file

@ -17,10 +17,10 @@
#include "platform.h" #include "platform.h"
#include "io.h" #include "drivers/io.h"
#include "io_impl.h" #include "io_impl.h"
#include "light_led.h" #include "drivers/light_led.h"
static const IO_t leds[] = { static const IO_t leds[] = {
#ifdef LED0 #ifdef LED0

View file

@ -23,10 +23,10 @@
#include "common/utils.h" #include "common/utils.h"
#include "time.h" #include "drivers/time.h"
#include "gpio.h" #include "drivers/gpio.h"
#include "light_led.h" #include "drivers/light_led.h"
void ledInit(void) void ledInit(void)

View file

@ -23,9 +23,9 @@
#include "common/utils.h" #include "common/utils.h"
#include "gpio.h" #include "drivers/gpio.h"
#include "light_led.h" #include "drivers/light_led.h"
void ledInit(void) void ledInit(void)
{ {

View file

@ -24,10 +24,10 @@
#include "common/color.h" #include "common/color.h"
#include "light_ws2811strip.h" #include "light_ws2811strip.h"
#include "nvic.h" #include "drivers/nvic.h"
#include "dma.h" #include "dma.h"
#include "io.h" #include "drivers/io.h"
#include "time.h" #include "drivers/time.h"
#include "rcc.h" #include "rcc.h"
#include "timer.h" #include "timer.h"

View file

@ -24,8 +24,8 @@
#include "common/color.h" #include "common/color.h"
#include "light_ws2811strip.h" #include "light_ws2811strip.h"
#include "nvic.h" #include "drivers/nvic.h"
#include "io.h" #include "drivers/io.h"
#include "dma.h" #include "dma.h"
#include "rcc.h" #include "rcc.h"
#include "timer.h" #include "timer.h"

View file

@ -22,8 +22,8 @@
#ifdef LED_STRIP #ifdef LED_STRIP
#include "io.h" #include "drivers/io.h"
#include "nvic.h" #include "drivers/nvic.h"
#include "common/color.h" #include "common/color.h"
#include "light_ws2811strip.h" #include "light_ws2811strip.h"

View file

@ -24,10 +24,10 @@
#include "common/color.h" #include "common/color.h"
#include "light_ws2811strip.h" #include "light_ws2811strip.h"
#include "nvic.h" #include "drivers/nvic.h"
#include "dma.h" #include "dma.h"
#include "io.h" #include "drivers/io.h"
#include "time.h" #include "drivers/time.h"
#include "rcc.h" #include "rcc.h"
#include "timer.h" #include "timer.h"

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