From c2ee6f0fad50d5085c9270ee1f849a578848156a Mon Sep 17 00:00:00 2001 From: MJ666 Date: Sun, 16 Dec 2018 11:46:14 +0100 Subject: [PATCH] STM32F405 Generic target ALIENFLIGHTF4 generic config --- .../target/STM32F405/config/ALIENFLIGHTNGF4.config | 121 +++++++++++++++++++++ src/main/target/STM32F405/target.c | 121 +++++++++++++++++++++ src/main/target/STM32F405/target.h | 116 ++++++++++++++++++++ src/main/target/STM32F405/target.mk | 8 ++ 4 files changed, 366 insertions(+) create mode 100644 src/main/target/STM32F405/config/ALIENFLIGHTNGF4.config create mode 100644 src/main/target/STM32F405/target.c create mode 100644 src/main/target/STM32F405/target.h create mode 100644 src/main/target/STM32F405/target.mk diff --git a/src/main/target/STM32F405/config/ALIENFLIGHTNGF4.config b/src/main/target/STM32F405/config/ALIENFLIGHTNGF4.config new file mode 100644 index 000000000..fc002d0d9 --- /dev/null +++ b/src/main/target/STM32F405/config/ALIENFLIGHTNGF4.config @@ -0,0 +1,121 @@ +# Name: ALIENFLIGHTNGF4 +# Description: ALIENFLIGHTNGF4 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 +set mag_bustype = I2C +set mag_i2c_device = 1 +set align_mag = CW180FLIP + +# Baro +set baro_bustype = I2C +set baro_i2c_device = 1 + +# 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 + +# Timers +# timer is zero origin +timer A08 0 +timer B00 1 +timer B01 1 +timer B14 0 +timer B15 0 +timer B08 0 +timer B09 0 +timer A00 1 +timer A01 1 +timer C06 1 +timer C07 1 +timer C08 1 +timer C09 1 +resource MOTOR 1 B08 +resource MOTOR 2 B09 +resource MOTOR 3 A00 +resource MOTOR 4 A01 +resource MOTOR 5 C06 +resource MOTOR 6 C07 +resource MOTOR 7 C08 +resource MOTOR 8 C09 +resource PWM 1 A08 +resource PWM 2 B00 +resource PWM 3 B01 +resource PWM 4 B14 +resource PWM 5 B15 +resource LED_STRIP 1 B15 +resource PPM 1 A08 + +# DMA stream conflict if burst mode is not used +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 INVERTER 2 C15 + +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 +resource ADC_EXT 1 C05 + +# 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 diff --git a/src/main/target/STM32F405/target.c b/src/main/target/STM32F405/target.c new file mode 100644 index 000000000..3eba13786 --- /dev/null +++ b/src/main/target/STM32F405/target.c @@ -0,0 +1,121 @@ +/* + * This file is part of Cleanflight and Betaflight. + * + * Cleanflight and Betaflight are free software. You can redistribute + * this software and/or modify this software under the terms of the + * GNU General Public License as published by the Free Software + * Foundation, either version 3 of the License, or (at your option) + * any later version. + * + * Cleanflight and Betaflight are distributed in the hope that they + * will be useful, but WITHOUT ANY WARRANTY; without even the implied + * warranty of MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. + * See the GNU General Public License for more details. + * + * You should have received a copy of the GNU General Public License + * along with this software. + * + * If not, see . + */ + +#include + +#include "platform.h" +#include "drivers/io.h" +#include "drivers/dma.h" + +#include "drivers/timer.h" +#include "drivers/timer_def.h" + +const timerHardware_t timerHardware[USABLE_TIMER_CHANNEL_COUNT] = { +// Auto-generated from 'timer_def.h' +//PORTA + DEF_TIM(TIM2, CH1, PA0, TIM_USE_ANY, 0, 0), + DEF_TIM(TIM2, CH2, PA1, TIM_USE_ANY, 0, 0), + DEF_TIM(TIM2, CH3, PA2, TIM_USE_ANY, 0, 0), + DEF_TIM(TIM2, CH4, PA3, TIM_USE_ANY, 0, 0), + DEF_TIM(TIM2, CH1, PA5, TIM_USE_ANY, 0, 0), + DEF_TIM(TIM1, CH1N, PA7, TIM_USE_ANY, 0, 0), + DEF_TIM(TIM1, CH1, PA8, TIM_USE_ANY, 0, 0), + DEF_TIM(TIM1, CH2, PA9, TIM_USE_ANY, 0, 0), + DEF_TIM(TIM1, CH3, PA10, TIM_USE_ANY, 0, 0), + DEF_TIM(TIM1, CH1N, PA11, TIM_USE_ANY, 0, 0), + DEF_TIM(TIM2, CH1, PA15, TIM_USE_ANY, 0, 0), + + DEF_TIM(TIM5, CH1, PA0, TIM_USE_ANY, 0, 0), + DEF_TIM(TIM5, CH2, PA1, TIM_USE_ANY, 0, 0), + DEF_TIM(TIM5, CH3, PA2, TIM_USE_ANY, 0, 0), + DEF_TIM(TIM5, CH4, PA3, TIM_USE_ANY, 0, 0), + DEF_TIM(TIM3, CH1, PA6, TIM_USE_ANY, 0, 0), + DEF_TIM(TIM3, CH2, PA7, TIM_USE_ANY, 0, 0), + + DEF_TIM(TIM9, CH1, PA2, TIM_USE_ANY, 0, 0), + DEF_TIM(TIM9, CH2, PA3, TIM_USE_ANY, 0, 0), + DEF_TIM(TIM8, CH1N, PA5, TIM_USE_ANY, 0, 0), + DEF_TIM(TIM8, CH1N, PA7, TIM_USE_ANY, 0, 0), + + DEF_TIM(TIM13, CH1, PA6, TIM_USE_ANY, 0, 0), + DEF_TIM(TIM14, CH1, PA7, TIM_USE_ANY, 0, 0), + +//PORTB + DEF_TIM(TIM1, CH2N, PB0, TIM_USE_ANY, 0, 0), + DEF_TIM(TIM1, CH3N, PB1, TIM_USE_ANY, 0, 0), + DEF_TIM(TIM2, CH2, PB3, TIM_USE_ANY, 0, 0), + DEF_TIM(TIM2, CH3, PB10, TIM_USE_ANY, 0, 0), + DEF_TIM(TIM2, CH4, PB11, TIM_USE_ANY, 0, 0), + DEF_TIM(TIM1, CH1N, PB13, TIM_USE_ANY, 0, 0), + DEF_TIM(TIM1, CH2N, PB14, TIM_USE_ANY, 0, 0), + DEF_TIM(TIM1, CH3N, PB15, TIM_USE_ANY, 0, 0), + + DEF_TIM(TIM3, CH3, PB0, TIM_USE_ANY, 0, 0), + DEF_TIM(TIM3, CH4, PB1, TIM_USE_ANY, 0, 0), + DEF_TIM(TIM3, CH1, PB4, TIM_USE_ANY, 0, 0), + DEF_TIM(TIM3, CH2, PB5, TIM_USE_ANY, 0, 0), + DEF_TIM(TIM4, CH1, PB6, TIM_USE_ANY, 0, 0), + DEF_TIM(TIM4, CH2, PB7, TIM_USE_ANY, 0, 0), + DEF_TIM(TIM4, CH3, PB8, TIM_USE_ANY, 0, 0), + DEF_TIM(TIM4, CH4, PB9, TIM_USE_ANY, 0, 0), + + DEF_TIM(TIM8, CH2N, PB0, TIM_USE_ANY, 0, 0), + DEF_TIM(TIM8, CH3N, PB1, TIM_USE_ANY, 0, 0), + DEF_TIM(TIM10, CH1, PB8, TIM_USE_ANY, 0, 0), + DEF_TIM(TIM11, CH1, PB9, TIM_USE_ANY, 0, 0), + DEF_TIM(TIM8, CH2N, PB14, TIM_USE_ANY, 0, 0), + DEF_TIM(TIM8, CH3N, PB15, TIM_USE_ANY, 0, 0), + + DEF_TIM(TIM12, CH1, PB14, TIM_USE_ANY, 0, 0), + DEF_TIM(TIM12, CH2, PB15, TIM_USE_ANY, 0, 0), + +//PORTC + DEF_TIM(TIM3, CH1, PC6, TIM_USE_ANY, 0, 0), + DEF_TIM(TIM3, CH2, PC7, TIM_USE_ANY, 0, 0), + DEF_TIM(TIM3, CH3, PC8, TIM_USE_ANY, 0, 0), + DEF_TIM(TIM3, CH4, PC9, TIM_USE_ANY, 0, 0), + + DEF_TIM(TIM8, CH1, PC6, TIM_USE_ANY, 0, 0), + DEF_TIM(TIM8, CH2, PC7, TIM_USE_ANY, 0, 0), + DEF_TIM(TIM8, CH3, PC8, TIM_USE_ANY, 0, 0), + DEF_TIM(TIM8, CH4, PC9, TIM_USE_ANY, 0, 0), + +//PORTD + DEF_TIM(TIM4, CH1, PD12, TIM_USE_ANY, 0, 0), + DEF_TIM(TIM4, CH2, PD13, TIM_USE_ANY, 0, 0), + DEF_TIM(TIM4, CH3, PD14, TIM_USE_ANY, 0, 0), + DEF_TIM(TIM4, CH4, PD15, TIM_USE_ANY, 0, 0), + +//PORTE + DEF_TIM(TIM1, CH1N, PE8, TIM_USE_ANY, 0, 0), + DEF_TIM(TIM1, CH1, PE9, TIM_USE_ANY, 0, 0), + DEF_TIM(TIM1, CH2N, PE10, TIM_USE_ANY, 0, 0), + DEF_TIM(TIM1, CH2, PE11, TIM_USE_ANY, 0, 0), + DEF_TIM(TIM1, CH3N, PE12, TIM_USE_ANY, 0, 0), + DEF_TIM(TIM1, CH3, PE13, TIM_USE_ANY, 0, 0), + DEF_TIM(TIM1, CH4, PE14, TIM_USE_ANY, 0, 0), + + DEF_TIM(TIM9, CH1, PE5, TIM_USE_ANY, 0, 0), + DEF_TIM(TIM9, CH2, PE6, TIM_USE_ANY, 0, 0), + +//PORTF + DEF_TIM(TIM10, CH1, PF6, TIM_USE_ANY, 0, 0), + DEF_TIM(TIM11, CH1, PF7, TIM_USE_ANY, 0, 0), +}; diff --git a/src/main/target/STM32F405/target.h b/src/main/target/STM32F405/target.h new file mode 100644 index 000000000..7d8fe173d --- /dev/null +++ b/src/main/target/STM32F405/target.h @@ -0,0 +1,116 @@ +/* + * This file is part of Cleanflight and Betaflight. + * + * Cleanflight and Betaflight are free software. You can redistribute + * this software and/or modify this software under the terms of the + * GNU General Public License as published by the Free Software + * Foundation, either version 3 of the License, or (at your option) + * any later version. + * + * Cleanflight and Betaflight are distributed in the hope that they + * will be useful, but WITHOUT ANY WARRANTY; without even the implied + * warranty of MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. + * See the GNU General Public License for more details. + * + * You should have received a copy of the GNU General Public License + * along with this software. + * + * If not, see . + */ + +#pragma once + +// Treat the target as generic, and expect manufacturer id / board name +// to be supplied when the board is configured for the first time +#define GENERIC_TARGET + +#define TARGET_BOARD_IDENTIFIER "S405" + +#define USBD_PRODUCT_STRING "S405" + +#define USE_BEEPER + +// MPU interrupt +#define USE_EXTI +#define USE_MPU_DATA_READY_SIGNAL +//#define DEBUG_MPU_DATA_READY_INTERRUPT +#define USE_GYRO_EXTI + +#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 USE_MAG +#define USE_MAG_HMC5883 +#define USE_MAG_SPI_HMC5883 +#define USE_MAG_QMC5883 +#define USE_MAG_LIS3MDL +#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 +#define USE_I2C_DEVICE_3 +#define I2C_FULL_RECONFIGURABILITY + +#define USE_VCP + +#define USE_UART1 +#define USE_UART2 +#define USE_UART3 +#define USE_UART4 +#define USE_UART5 +#define USE_UART6 +#define USE_SOFTSERIAL1 +#define USE_SOFTSERIAL2 +#define USE_INVERTER +#define SERIAL_PORT_COUNT 9 + +#define USE_ESCSERIAL + +#define USE_SPI +#define USE_SPI_DEVICE_1 +#define USE_SPI_DEVICE_2 +#define USE_SPI_DEVICE_3 +#define SPI_FULL_RECONFIGURABILITY + +#define USE_ADC + +#define USE_SERIAL_4WAY_BLHELI_INTERFACE + +#define TARGET_IO_PORTA 0xffff +#define TARGET_IO_PORTB 0xffff +#define TARGET_IO_PORTC 0xffff +#define TARGET_IO_PORTD 0xffff +#define TARGET_IO_PORTE 0xffff +#define TARGET_IO_PORTF 0xffff + +#define USABLE_TIMER_CHANNEL_COUNT 70 + +#define USE_TIMER_MGMT diff --git a/src/main/target/STM32F405/target.mk b/src/main/target/STM32F405/target.mk new file mode 100644 index 000000000..4c85a12d4 --- /dev/null +++ b/src/main/target/STM32F405/target.mk @@ -0,0 +1,8 @@ +F405_TARGETS += $(TARGET) +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/max7456.c -- 2.11.4.GIT