From 060759d9f1c04cd3175e0c8480abdfa4b629d465 Mon Sep 17 00:00:00 2001 From: mikeller Date: Fri, 1 Mar 2019 04:21:03 +1300 Subject: [PATCH] Added STM32F745 unified target. --- src/main/target/STM32F745/target.c | 22 +++++ src/main/target/STM32F745/target.h | 118 +++++++++++++++++++++++ src/main/target/STM32F745/target.mk | 8 ++ unified_targets/configs/OMNIBUSF7V2.config | 144 +++++++++++++++++++++++++++++ unified_targets/docs/Manufacturers.md | 1 + 5 files changed, 293 insertions(+) create mode 100644 src/main/target/STM32F745/target.c create mode 100644 src/main/target/STM32F745/target.h create mode 100644 src/main/target/STM32F745/target.mk create mode 100644 unified_targets/configs/OMNIBUSF7V2.config diff --git a/src/main/target/STM32F745/target.c b/src/main/target/STM32F745/target.c new file mode 100644 index 000000000..a087e06bd --- /dev/null +++ b/src/main/target/STM32F745/target.c @@ -0,0 +1,22 @@ +/* + * 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 . + */ + +// Needed to suppress the pedantic warning about an empty file +#include diff --git a/src/main/target/STM32F745/target.h b/src/main/target/STM32F745/target.h new file mode 100644 index 000000000..959d6909b --- /dev/null +++ b/src/main/target/STM32F745/target.h @@ -0,0 +1,118 @@ +/* + * 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 USE_UNIFIED_TARGET + +#define TARGET_BOARD_IDENTIFIER "S745" + +#define USBD_PRODUCT_STRING "Betaflight STM32F745" + +#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_MPU6000 +#define USE_GYRO_SPI_MPU6000 +#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 USE_I2C_DEVICE_4 +#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_UART7 +#define USE_UART8 +#define USE_SOFTSERIAL1 +#define USE_SOFTSERIAL2 + +#define SERIAL_PORT_COUNT 11 + +#define USE_ESCSERIAL + +#define USE_SPI +#define USE_SPI_DEVICE_1 +#define USE_SPI_DEVICE_2 +#define USE_SPI_DEVICE_3 +#define USE_SPI_DEVICE_4 +#define USE_SPI_DEVICE_5 +#define USE_SPI_DEVICE_6 +#define SPI_FULL_RECONFIGURABILITY + +#define USE_ADC + +#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 diff --git a/src/main/target/STM32F745/target.mk b/src/main/target/STM32F745/target.mk new file mode 100644 index 000000000..8455db649 --- /dev/null +++ b/src/main/target/STM32F745/target.mk @@ -0,0 +1,8 @@ +F7X5XG_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 diff --git a/unified_targets/configs/OMNIBUSF7V2.config b/unified_targets/configs/OMNIBUSF7V2.config new file mode 100644 index 000000000..1c1f15d02 --- /dev/null +++ b/unified_targets/configs/OMNIBUSF7V2.config @@ -0,0 +1,144 @@ +# Betaflight / OMNIBUSF7V2 (OB72) 4.0.0 Mar 1 2019 / 03:53:33 (6cacaf00a) MSP API: 1.41 + +board_name OMNIBUSF7V2 +manufacturer_id AIRB + +# resources +resource BEEPER 1 D15 +resource MOTOR 1 B00 +resource MOTOR 2 B01 +resource MOTOR 3 E09 +resource MOTOR 4 E11 +resource PPM 1 A03 +resource SONAR_TRIGGER 1 B10 +resource SONAR_ECHO 1 B11 +resource LED_STRIP 1 D12 +resource SERIAL_TX 1 A09 +resource SERIAL_TX 3 B10 +resource SERIAL_TX 6 C06 +resource SERIAL_RX 1 A10 +resource SERIAL_RX 2 A03 +resource SERIAL_RX 3 B11 +resource SERIAL_RX 6 C07 +resource SERIAL_RX 7 E07 +resource LED 1 E00 +resource SPI_SCK 1 A05 +resource SPI_SCK 2 B13 +resource SPI_SCK 3 C10 +resource SPI_SCK 4 E02 +resource SPI_MISO 1 A06 +resource SPI_MISO 2 B14 +resource SPI_MISO 3 C11 +resource SPI_MISO 4 E05 +resource SPI_MOSI 1 A07 +resource SPI_MOSI 2 B15 +resource SPI_MOSI 3 C12 +resource SPI_MOSI 4 E06 +resource ESCSERIAL 1 A02 +resource ADC_BATT 1 C03 +resource ADC_RSSI 1 C05 +resource ADC_CURR 1 C02 +resource BARO_CS 1 A01 +resource SDCARD_CS 1 E04 +resource SDCARD_DETECT 1 E03 +resource OSD_CS 1 B12 +resource GYRO_EXTI 1 D00 +resource GYRO_EXTI 2 E08 +resource GYRO_CS 1 A15 +resource GYRO_CS 2 A04 +resource USB_DETECT 1 C04 + +# timer +timer E13 0 +timer B00 0 +timer B01 1 +timer E09 0 +timer E11 0 +timer D12 0 +timer B10 0 +timer B11 0 +timer C06 1 +timer C07 1 +timer A03 0 +timer A02 2 + +# dmaopt +dmaopt SPI_TX 4 0 +# SPI_TX 4: DMA2 Stream 1 Channel 4 +dmaopt ADC 1 1 +# ADC 1: DMA2 Stream 4 Channel 0 +dmaopt pin E13 1 +# pin E13: DMA2 Stream 6 Channel 6 +dmaopt pin B00 0 +# pin B00: DMA1 Stream 7 Channel 5 +dmaopt pin B01 0 +# pin B01: DMA1 Stream 2 Channel 5 +dmaopt pin E09 2 +# pin E09: DMA2 Stream 3 Channel 6 +dmaopt pin E11 1 +# pin E11: DMA2 Stream 2 Channel 6 +dmaopt pin D12 0 +# pin D12: DMA1 Stream 0 Channel 2 +dmaopt pin B10 0 +# pin B10: DMA1 Stream 1 Channel 3 +dmaopt pin B11 0 +# pin B11: DMA1 Stream 7 Channel 3 +dmaopt pin C06 0 +# pin C06: DMA2 Stream 2 Channel 0 +dmaopt pin C07 1 +# pin C07: DMA2 Stream 3 Channel 7 +dmaopt pin A03 0 +# pin A03: DMA1 Stream 7 Channel 3 + +feature RX_SERIAL +feature OSD +feature AIRMODE +feature ANTI_GRAVITY +feature DYNAMIC_FILTER + +# serial +serial 1 64 115200 57600 0 115200 +serial 6 1024 115200 57600 0 115200 + +# master +set gyro_to_use = FIRST +set align_mag = DEFAULT +set mag_bustype = I2C +set mag_i2c_device = 2 +set mag_i2c_address = 0 +set mag_spi_device = 0 +set mag_hardware = AUTO +set baro_bustype = SPI +set baro_spi_device = 1 +set baro_i2c_device = 0 +set baro_i2c_address = 0 +set baro_hardware = AUTO +set serialrx_provider = SBUS +set adc_device = 1 +set motor_pwm_protocol = ONESHOT125 +set current_meter = ADC +set battery_meter = ADC +set beeper_inversion = ON +set beeper_od = OFF +set tlm_halfduplex = ON +set sdcard_detect_inverted = ON +set sdcard_mode = SPI +set sdcard_dma = OFF +set sdcard_spi_bus = 4 +set system_hse_mhz = 8 +set max7456_clock = DEFAULT +set max7456_spi_bus = 2 +set max7456_preinit_opu = OFF +set dashboard_i2c_bus = 2 +set dashboard_i2c_addr = 60 +set usb_msc_pin_pullup = ON +set gyro_1_bustype = SPI +set gyro_1_spibus = 3 +set gyro_1_i2cBus = 0 +set gyro_1_i2c_address = 0 +set gyro_1_sensor_align = CW90 +set gyro_2_bustype = SPI +set gyro_2_spibus = 1 +set gyro_2_i2cBus = 0 +set gyro_2_i2c_address = 0 +set gyro_2_sensor_align = DEFAULT diff --git a/unified_targets/docs/Manufacturers.md b/unified_targets/docs/Manufacturers.md index 157502d3b..96c080201 100644 --- a/unified_targets/docs/Manufacturers.md +++ b/unified_targets/docs/Manufacturers.md @@ -4,6 +4,7 @@ Last updated: 17/02/2019 |-|-|-| |CUST|'Custom', to be used for homebrew targets|| |AFNG|AlienFlight NG|https://www.alienflightng.com/| +|AIRB|Airbot|https://store.myairbot.com/| |BKMN|Jason Blackman|https://github.com/blckmn| |DRCL|dronercland|https://www.instagram.com/dronercland/| |DYST|DongYang Smart Technology Co.,Ltd (dys)|http://www.dys.hk/| -- 2.11.4.GIT