Update STM32F7X2 generic target

Add more sensor drivers
Update NERO.config
Add ALIENFLIGHTNG F7 generic target config
Add AlienFlightNG F7 Dual generic config
This commit is contained in:
MJ666 2018-09-18 20:57:45 +02:00
parent 8165039e4e
commit 3ca69b7b53
7 changed files with 272 additions and 8 deletions

View File

@ -53,7 +53,7 @@ static void gyroResetSpiDeviceConfig(gyroDeviceConfig_t *devconf, SPI_TypeDef *i
}
#endif
#ifdef USE_I2C_GYRO
#if defined(USE_I2C_GYRO) && !defined(USE_MULTI_GYRO)
static void gyroResetI2cDeviceConfig(gyroDeviceConfig_t *devconf, I2CDevice i2cbus, ioTag_t extiTag, uint8_t align)
{
devconf->bustype = BUSTYPE_I2C;

View File

@ -0,0 +1,121 @@
# Name: ALIENFLIGHTNGF7
# Description: ALIENFLIGHTNGF7 Standard target configuration
defaults nosave
# Basic I/O
resource LED 1 C12
resource LED 2 D02
resource BEEPER 1 C13
set beeper_inversion = ON
set beeper_od = OFF
# Buses
resource I2C_SCL 1 B06
resource I2C_SDA 1 B07
resource SPI_SCK 1 A05
resource SPI_MISO 1 A06
resource SPI_MOSI 1 A07
resource SPI_SCK 2 B13
resource SPI_MISO 2 C02
resource SPI_MOSI 2 C03
resource SPI_SCK 3 B03
resource SPI_MISO 3 B04
resource SPI_MOSI 3 B05
# Acc/gyro
resource GYRO_CS 1 A04
resource GYRO_EXTI 1 C14
set gyro_1_bustype = SPI
set gyro_1_spibus = 1
set gyro_1_sensor_align = CW270
# Compass
resource COMPASS_CS 1 C15
set mag_bustype = SPI
set mag_spi_device = 3
set align_mag = CW180FLIP
# Baro
resource BARO_CS 1 A15
set baro_bustype = SPI
set baro_spi_device = 3
# SDCard
resource SDCARD_CS 1 B10
resource SDCARD_DETECT 1 B11
set sdcard_detect_inverted = ON
set sdcard_mode = SPI
set sdcard_spi_bus = 2
# SPI Flash
resource FLASH_CS 1 B12
set flash_spi_bus = 2
# OSD
resource OSD_CS 1 B12
set max7456_spi_bus = 3
# Timers
# timer is zero origin
timer A08 0
timer C06 1
timer C07 0
timer B14 1
timer B00 1
timer A00 1
timer C08 1
timer A01 1
timer C09 1
timer B01 1
timer B15 0
timer B08 1
timer B09 1
resource MOTOR 1 C06
resource MOTOR 2 C07
resource MOTOR 3 B14
resource MOTOR 4 B00
resource MOTOR 5 A00
resource MOTOR 6 C08
resource MOTOR 7 A01
resource MOTOR 8 C09
resource LED_STRIP 1 A08
resource PPM 1 A08
# DMA stream conflict if burst mode is not used
# XXX Need a mechanism to specify dmaopt
set dshot_burst = ON
# Serial ports
resource SERIAL_TX 1 A09
resource SERIAL_RX 1 A10
resource SERIAL_TX 2 A02
resource SERIAL_RX 2 A03
resource SERIAL_TX 4 C10
resource SERIAL_RX 4 C11
# ADC
resource ADC_BATT 1 C00
resource ADC_RSSI 1 C04
resource ADC_CURR 1 C01
# Remaining
resource RX_BIND_PLUG 1 B02
resource ESCSERIAL 1 A08
# Some configs
feature RX_SERIAL
feature MOTOR_STOP
map TAER1234
serial 0 0 115200 57600 0 115200
serial 1 64 115200 57600 0 115200
serial 3 0 115200 57600 0 115200
set serialrx_provider = SPEK2048
set spektrum_sat_bind = 5
set blackbox_device = SDCARD
set battery_meter = ADC

View File

@ -0,0 +1,111 @@
# Name: ALIENFLIGHTNGF7
# Description: ALIENFLIGHTNGF7 Standard target configuration
defaults nosave
# Basic I/O
resource LED 1 C12
resource LED 2 D02
resource BEEPER 1 C13
set beeper_inversion = ON
set beeper_od = OFF
# Buses
resource I2C_SCL 1 B06
resource I2C_SDA 1 B07
resource SPI_SCK 1 A05
resource SPI_MISO 1 A06
resource SPI_MOSI 1 A07
resource SPI_SCK 2 B13
resource SPI_MISO 2 C02
resource SPI_MOSI 2 C03
resource SPI_SCK 3 B03
resource SPI_MISO 3 B04
resource SPI_MOSI 3 B05
# Acc/gyro
resource GYRO_CS 1 A04
resource GYRO_EXTI 1 C14
set gyro_1_bustype = SPI
set gyro_1_spibus = 1
set gyro_1_sensor_align = CW270
resource GYRO_CS 2 A15
resource GYRO_EXTI 2 C15
set gyro_1_bustype = SPI
set gyro_1_spibus = 3
set gyro_1_sensor_align = CW270
# SDCard
resource SDCARD_CS 1 B10
resource SDCARD_DETECT 1 B11
set sdcard_detect_inverted = ON
set sdcard_mode = SPI
set sdcard_spi_bus = 2
# OSD
resource OSD_CS 1 B12
set max7456_spi_bus = 3
# Timers
# timer is zero origin
timer A08 0
timer C06 1
timer C07 0
timer B14 1
timer B00 1
timer A00 1
timer C08 1
timer A01 1
timer C09 1
timer B01 1
timer B15 0
timer B08 1
timer B09 1
resource MOTOR 1 C06
resource MOTOR 2 C07
resource MOTOR 3 B14
resource MOTOR 4 B00
resource MOTOR 5 A00
resource MOTOR 6 C08
resource MOTOR 7 A01
resource MOTOR 8 C09
resource LED_STRIP 1 A08
resource PPM 1 A08
# DMA stream conflict if burst mode is not used
# XXX Need a mechanism to specify dmaopt
set dshot_burst = ON
# Serial ports
resource SERIAL_TX 1 A09
resource SERIAL_RX 1 A10
resource SERIAL_TX 2 A02
resource SERIAL_RX 2 A03
resource SERIAL_TX 4 C10
resource SERIAL_RX 4 C11
# ADC
resource ADC_BATT 1 C00
resource ADC_RSSI 1 C04
resource ADC_CURR 1 C01
# Remaining
resource RX_BIND_PLUG 1 B02
resource ESCSERIAL 1 A08
# Some configs
feature RX_SERIAL
feature MOTOR_STOP
map TAER1234
serial 0 0 115200 57600 0 115200
serial 1 64 115200 57600 0 115200
serial 3 0 115200 57600 0 115200
set serialrx_provider = SPEK2048
set spektrum_sat_bind = 5
set blackbox_device = SDCARD
set battery_meter = ADC

View File

@ -41,6 +41,13 @@ set gyro_1_spibus = 1
set gyro_1_sensor_align = CW0
#set gyro_1_hardware = MPU6500 # Not working (yet ... will it ever?)
# SDCard
resource SDCARD_CS 1 A15
resource SDCARD_DETECT 1 D02
set sdcard_detect_inverted = ON
set sdcard_mode = SPI
setsdcard_spi_bus = 3
# Timers
# First four timers
# timer is zero origin

View File

@ -39,26 +39,40 @@
#define USE_ACC
#define USE_GYRO
#define USE_ACC_MPU6050
#define USE_GYRO_MPU6050
#define USE_ACC_MPU6500
#define USE_GYRO_MPU6500
#define USE_ACC_SPI_MPU6500
#define USE_GYRO_SPI_MPU6500
#define USE_ACC_SPI_ICM20689
#define USE_GYRO_SPI_ICM20689
// Other USE_ACCs and USE_GYROs should follow
#define GYRO_CONFIG_USE_GYRO_DEFAULT GYRO_CONFIG_USE_GYRO_1
#define USE_MAG
#define USE_MAG_HMC5883
#define USE_MAG_SPI_HMC5883
#define USE_MAG_QMC5883
#define USE_MAG_LIS3MDL
#define MAG_HMC5883_ALIGN CW270_DEG_FLIP
#define USE_MAG_AK8963
#define USE_MAG_SPI_AK8963
#define USE_BARO
#define USE_BARO_MS5611
#define USE_BARO_SPI_MS5611
#define USE_BARO_BMP280
#define USE_BARO_SPI_BMP280
#define USE_BARO_LPS
#define USE_BARO_SPI_LPS
#define USE_SDCARD
#define USE_SDCARD_SPI
#define USE_FLASHFS
#define USE_FLASH_M25P16
#define USE_MAX7456
#define USE_I2C
#define USE_I2C_DEVICE_1
#define USE_I2C_DEVICE_2

View File

@ -1,9 +1,8 @@
F7X2RE_TARGETS += $(TARGET)
FEATURES += SDCARD_SPI VCP
FEATURES += SDCARD_SPI VCP ONBOARDFLASH
TARGET_SRC = \
$(addprefix drivers/accgyro/,$(notdir $(wildcard $(SRC_DIR)/drivers/accgyro/*.c))) \
$(addprefix drivers/barometer/,$(notdir $(wildcard $(SRC_DIR)/drivers/barometer/*.c))) \
$(addprefix drivers/compass/,$(notdir $(wildcard $(SRC_DIR)/drivers/compass/*.c))) \
drivers/light_ws2811strip.c \
drivers/light_ws2811strip_hal.c
drivers/max7456.c

View File

@ -54,6 +54,18 @@
#endif
#endif
// pg/flash
#ifdef USE_FLASH_M25P16
#ifndef FLASH_CS_PIN
#define FLASH_CS_PIN NONE
#endif
#ifndef FLASH_SPI_INSTANCE
#define FLASH_SPI_INSTANCE NULL
#endif
#endif
// pg/bus_i2c
#ifdef I2C_FULL_RECONFIGURABILITY
@ -281,7 +293,7 @@
#endif
#if !defined(ACC_1_ALIGN)
#define ACC_1_ALIGN ALIGN_DEFAULT
#define ACC_1_ALIGN ALIGN_DEFAULT
#endif
#if defined(MPU_ADDRESS)