diff --git a/src/main/drivers/timer.h b/src/main/drivers/timer.h index 7bd661b47c..553128c77e 100644 --- a/src/main/drivers/timer.h +++ b/src/main/drivers/timer.h @@ -167,11 +167,11 @@ extern const timerHardware_t timerHardware[]; #endif #if defined(USE_TIMER_MGMT) -#if defined(STM32F40_41xxx) +#if defined(STM32F4) #define FULL_TIMER_CHANNEL_COUNT 70 -#elif defined(STM32F722xx) +#elif defined(STM32F7) #define FULL_TIMER_CHANNEL_COUNT 70 diff --git a/src/main/drivers/timer_stm32f4xx.c b/src/main/drivers/timer_stm32f4xx.c index 18fb1ba731..bc32282089 100644 --- a/src/main/drivers/timer_stm32f4xx.c +++ b/src/main/drivers/timer_stm32f4xx.c @@ -53,7 +53,6 @@ const timerDef_t timerDefinitions[HARDWARE_TIMER_DEFINITION_COUNT] = { }; #if defined(USE_TIMER_MGMT) -#if defined(STM32F40_41xxx) const timerHardware_t fullTimerHardware[FULL_TIMER_CHANNEL_COUNT] = { // Auto-generated from 'timer_def.h' //PORTA @@ -147,7 +146,6 @@ const timerHardware_t fullTimerHardware[FULL_TIMER_CHANNEL_COUNT] = { DEF_TIM(TIM11, CH1, PF7, TIM_USE_ANY, 0, 0), }; #endif -#endif // USE_TIMER_MGMT /* diff --git a/src/main/drivers/timer_stm32f7xx.c b/src/main/drivers/timer_stm32f7xx.c index a34d1f4b3a..03ba6ab1ee 100644 --- a/src/main/drivers/timer_stm32f7xx.c +++ b/src/main/drivers/timer_stm32f7xx.c @@ -48,8 +48,6 @@ const timerDef_t timerDefinitions[HARDWARE_TIMER_DEFINITION_COUNT] = { }; #if defined(USE_TIMER_MGMT) -#if defined(STM32F722xx) - const timerHardware_t fullTimerHardware[FULL_TIMER_CHANNEL_COUNT] = { // Auto-generated from 'timer_def.h' //PORTA @@ -142,7 +140,6 @@ const timerHardware_t fullTimerHardware[FULL_TIMER_CHANNEL_COUNT] = { DEF_TIM(TIM11, CH1, PF7, TIM_USE_ANY, 0, 0), }; #endif -#endif // USE_TIMER_MGMT /* diff --git a/src/main/target/STM32F405/target.h b/src/main/target/STM32F405/target.h index a2d3e3af70..7edb5570be 100644 --- a/src/main/target/STM32F405/target.h +++ b/src/main/target/STM32F405/target.h @@ -26,7 +26,7 @@ #define TARGET_BOARD_IDENTIFIER "S405" -#define USBD_PRODUCT_STRING "S405" +#define USBD_PRODUCT_STRING "Betaflight STM32F405" #define USE_BEEPER diff --git a/src/main/target/STM32F411/target.c b/src/main/target/STM32F411/target.c new file mode 100644 index 0000000000..a087e06bd2 --- /dev/null +++ b/src/main/target/STM32F411/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/STM32F411/target.h b/src/main/target/STM32F411/target.h new file mode 100644 index 0000000000..9090968603 --- /dev/null +++ b/src/main/target/STM32F411/target.h @@ -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 . + */ + +#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 "S411" + +#define USBD_PRODUCT_STRING "Betaflight STM32F411" + +#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 I2C_FULL_RECONFIGURABILITY + +#define USE_VCP + +#define USE_UART1 +#define USE_UART2 +#define USE_UART6 +#define USE_SOFTSERIAL1 +#define USE_SOFTSERIAL2 +#define USE_INVERTER +#define SERIAL_PORT_COUNT 6 + +#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 + +//TODO: Make this work with runtime configurability +//#define USE_RX_FRSKY_SPI_D +//#define USE_RX_FRSKY_SPI_X +//#define USE_RX_SFHSS_SPI +//#define USE_RX_FRSKY_SPI_TELEMETRY +//#define USE_RX_CC2500_SPI_PA_LNA +//#define USE_RX_CC2500_SPI_DIVERSITY + +//TODO: Make this work with runtime configurability +//#define USE_RX_FLYSKY +//#define USE_RX_FLYSKY_SPI_LED + +#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/STM32F411/target.mk b/src/main/target/STM32F411/target.mk new file mode 100644 index 0000000000..47a7d89b33 --- /dev/null +++ b/src/main/target/STM32F411/target.mk @@ -0,0 +1,17 @@ +F411_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 \ + drivers/rx/rx_cc2500.c \ + rx/cc2500_common.c \ + rx/cc2500_frsky_shared.c \ + rx/cc2500_frsky_d.c \ + rx/cc2500_frsky_x.c \ + rx/cc2500_sfhss.c \ + drivers/rx/rx_a7105.c \ + rx/a7105_flysky.c diff --git a/src/main/target/STM32F411DISCOVERY/target.h b/src/main/target/STM32F411DISCOVERY/target.h index 27587f9e0b..5610073b53 100644 --- a/src/main/target/STM32F411DISCOVERY/target.h +++ b/src/main/target/STM32F411DISCOVERY/target.h @@ -21,7 +21,7 @@ #pragma once #define TARGET_BOARD_IDENTIFIER "S411" // STM Discovery F411 -#define USBD_PRODUCT_STRING "DISCF411" +#define USBD_PRODUCT_STRING "STM32F411DISCOVERY" #define USE_SENSOR_NAMES diff --git a/src/main/target/STM32F4DISCOVERY/target.h b/src/main/target/STM32F4DISCOVERY/target.h index eb3195fdb2..2693042cda 100644 --- a/src/main/target/STM32F4DISCOVERY/target.h +++ b/src/main/target/STM32F4DISCOVERY/target.h @@ -21,7 +21,7 @@ #pragma once #define TARGET_BOARD_IDENTIFIER "SDF4" -#define USBD_PRODUCT_STRING "DISCF4" +#define USBD_PRODUCT_STRING "STM32F4DISCOVERY" #define USE_VTX_TABLE #define USE_SPI_TRANSACTION diff --git a/src/main/target/STM32F745/target.c b/src/main/target/STM32F745/target.c new file mode 100644 index 0000000000..a087e06bd2 --- /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 0000000000..959d6909bd --- /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 0000000000..8455db6492 --- /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/src/main/target/STM32F7X2/target.h b/src/main/target/STM32F7X2/target.h index 23fbcc2ee0..f5795738bd 100644 --- a/src/main/target/STM32F7X2/target.h +++ b/src/main/target/STM32F7X2/target.h @@ -26,7 +26,7 @@ #define TARGET_BOARD_IDENTIFIER "S7X2" -#define USBD_PRODUCT_STRING "S7X2" +#define USBD_PRODUCT_STRING "Betaflight STM32F7x2" #define USE_BEEPER diff --git a/src/main/target/common_pre.h b/src/main/target/common_pre.h index 6da9457725..8a145fd2f7 100644 --- a/src/main/target/common_pre.h +++ b/src/main/target/common_pre.h @@ -63,6 +63,7 @@ #define USE_USB_MSC #define USE_PERSISTENT_MSC_RTC #define USE_DMA_SPEC +#define USE_TIMER_MGMT // Re-enable this after 4.0 has been released, and remove the define from STM32F4DISCOVERY //#define USE_SPI_TRANSACTION @@ -70,10 +71,6 @@ #define USE_OVERCLOCK #endif -#if defined(STM32F40_41xxx) -#define USE_TIMER_MGMT -#endif - #endif // STM32F4 #ifdef STM32F7 @@ -91,13 +88,9 @@ #define USE_PERSISTENT_MSC_RTC #define USE_MCO #define USE_DMA_SPEC +#define USE_TIMER_MGMT // Re-enable this after 4.0 has been released, and remove the define from STM32F4DISCOVERY //#define USE_SPI_TRANSACTION - -#if defined(STM32F722xx) -#define USE_TIMER_MGMT -#endif - #endif // STM32F7 #if defined(STM32F4) || defined(STM32F7) diff --git a/unified_targets/configs/CRAZYBEEF4FR.config b/unified_targets/configs/CRAZYBEEF4FR.config new file mode 100644 index 0000000000..0696788739 --- /dev/null +++ b/unified_targets/configs/CRAZYBEEF4FR.config @@ -0,0 +1,95 @@ +# Betaflight / CRAZYBEEF4FR (C4FR) 4.0.0 Feb 28 2019 / 18:10:50 (b63a3e117) MSP API: 1.41 + +# This is not usable yet, as the SPI RX is not fully runtime configurable yet + +board_name CRAZYBEEF4FR +manufacturer_id HAMO + +# resources +resource BEEPER 1 C15 +resource MOTOR 1 B10 +resource MOTOR 2 B06 +resource MOTOR 3 B07 +resource MOTOR 4 B08 +resource PPM 1 A03 +resource PWM 1 A02 +resource PWM 2 A09 +resource PWM 3 A10 +resource LED_STRIP 1 A00 +resource SERIAL_TX 1 A09 +resource SERIAL_TX 2 A02 +resource SERIAL_RX 1 A10 +resource SERIAL_RX 2 A03 +resource LED 1 C13 +resource RX_BIND_PLUG 1 B02 +resource SPI_SCK 1 A05 +resource SPI_SCK 2 B13 +resource SPI_SCK 3 B03 +resource SPI_MISO 1 A06 +resource SPI_MISO 2 B14 +resource SPI_MISO 3 B04 +resource SPI_MOSI 1 A07 +resource SPI_MOSI 2 B15 +resource SPI_MOSI 3 B05 +resource ADC_BATT 1 B00 +resource ADC_CURR 1 B01 +resource OSD_CS 1 B12 +resource RX_SPI_CS 1 A15 +resource RX_SPI_BIND 1 B02 +resource RX_SPI_LED 1 B09 +resource GYRO_EXTI 1 A01 +resource GYRO_CS 1 A04 + +# timer +timer A03 2 +timer B10 0 +timer B06 0 +timer B07 0 +timer B08 0 +timer A00 1 +timer A02 2 +timer A09 0 +timer A10 0 + +# dmaopt +dmaopt ADC 1 0 +# ADC 1: DMA2 Stream 0 Channel 0 +dmaopt pin B10 0 +# pin B10: DMA1 Stream 1 Channel 3 +dmaopt pin B06 0 +# pin B06: DMA1 Stream 0 Channel 2 +dmaopt pin B07 0 +# pin B07: DMA1 Stream 3 Channel 2 +dmaopt pin B08 0 +# pin B08: DMA1 Stream 7 Channel 2 +dmaopt pin A00 0 +# pin A00: DMA1 Stream 2 Channel 6 +dmaopt pin A09 0 +# pin A09: DMA2 Stream 6 Channel 0 +dmaopt pin A10 0 +# pin A10: DMA2 Stream 6 Channel 0 + +# feature +feature TELEMETRY +feature OSD +feature AIRMODE +feature RX_SPI +feature ANTI_GRAVITY +feature DYNAMIC_FILTER + +# master +set rx_spi_protocol = FRSKY_X +set rx_spi_bus = 3 +set rx_spi_led_inversion = OFF +set adc_device = 1 +set motor_pwm_protocol = DSHOT600 +set beeper_inversion = ON +set beeper_od = OFF +set max7456_clock = DEFAULT +set max7456_spi_bus = 2 +set max7456_preinit_opu = OFF +set gyro_1_bustype = SPI +set gyro_1_spibus = 1 +set gyro_1_i2cBus = 0 +set gyro_1_i2c_address = 0 +set gyro_1_sensor_align = CW90 diff --git a/unified_targets/configs/MATEKF411.config b/unified_targets/configs/MATEKF411.config new file mode 100644 index 0000000000..243d75df64 --- /dev/null +++ b/unified_targets/configs/MATEKF411.config @@ -0,0 +1,98 @@ +board_name MATEKF411 +manufacturer_id MTKS + +# resources +resource BEEPER 1 B02 +resource MOTOR 1 B04 +resource MOTOR 2 B05 +resource MOTOR 3 B06 +resource MOTOR 4 B07 +resource MOTOR 5 B03 +resource MOTOR 6 B10 +resource PPM 1 A03 +resource LED_STRIP 1 A08 +resource SERIAL_TX 1 A09 +resource SERIAL_TX 2 A02 +resource SERIAL_RX 1 A10 +resource SERIAL_RX 2 A03 +resource LED 1 C13 +resource LED 2 C14 +resource SPI_SCK 1 A05 +resource SPI_SCK 2 B13 +resource SPI_MISO 1 A06 +resource SPI_MISO 2 B14 +resource SPI_MOSI 1 A07 +resource SPI_MOSI 2 B15 +resource ADC_BATT 1 B00 +resource ADC_CURR 1 B01 +resource GYRO_EXTI 1 A01 +resource GYRO_EXTI 2 NONE +resource GYRO_CS 1 A04 +resource USB_DETECT 1 C15 + +# timer list +timer A03 2 +timer B04 0 +timer B05 0 +timer B06 0 +timer B07 0 +timer B03 0 +timer B10 0 +timer A00 1 +timer A02 1 +timer A08 0 + +# dmaopt +dmaopt ADC 1 0 +# ADC 1: DMA2 Stream 0 Channel 0 +dmaopt pin B04 0 +# pin B04: DMA1 Stream 4 Channel 5 +dmaopt pin B05 0 +# pin B05: DMA1 Stream 5 Channel 5 +dmaopt pin B06 0 +# pin B06: DMA1 Stream 0 Channel 2 +dmaopt pin B07 0 +# pin B07: DMA1 Stream 3 Channel 2 +dmaopt pin B03 0 +# pin B03: DMA1 Stream 6 Channel 3 +dmaopt pin B10 0 +# pin B10: DMA1 Stream 1 Channel 3 +dmaopt pin A00 0 +# pin A00: DMA1 Stream 2 Channel 6 +dmaopt pin A02 0 +# pin A02: DMA1 Stream 0 Channel 6 +dmaopt pin A08 0 +# pin A08: DMA2 Stream 6 Channel 0 + +# feature +feature RX_SERIAL +feature SOFTSERIAL +feature TELEMETRY +feature OSD +feature AIRMODE +feature ANTI_GRAVITY +feature DYNAMIC_FILTER + +# serial +serial 0 64 115200 57600 0 115200 + +# master +set serialrx_provider = SBUS +set motor_pwm_protocol = ONESHOT125 +set current_meter = ADC +set battery_meter = ADC +set vbat_detect_cell_voltage = 300 +set system_hse_mhz = 8 +set max7456_clock = DEFAULT +set max7456_spi_bus = 2 +set max7456_preinit_opu = OFF +set gyro_1_bustype = SPI +set gyro_1_spibus = 1 +set gyro_1_i2cBus = 0 +set gyro_1_i2c_address = 0 +set gyro_1_sensor_align = CW180 +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/configs/OMNIBUSF7V2.config b/unified_targets/configs/OMNIBUSF7V2.config new file mode 100644 index 0000000000..1c1f15d02b --- /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 4548742116..96c0802018 100644 --- a/unified_targets/docs/Manufacturers.md +++ b/unified_targets/docs/Manufacturers.md @@ -4,9 +4,12 @@ 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/| |FFPV|Furious FPV|https://furiousfpv.com/| +|HAMO|Happymodel|http://www.happymodel.cn/| +|MTKS|Matek Systems|http://www.mateksys.com/| This is the official list of manufacturer ids (`manufacturer_id` in the target config) that will be supported for loading onto unified targets by Betaflight configurator.