Merge pull request #7857 from iFlightFpv/add_config_IFF4_TWIN_G

Add unified target config for IFlightF4_Twin_G board.
This commit is contained in:
Michael Keller 2019-03-25 12:44:42 +13:00 committed by GitHub
commit 6f93d526b7
No known key found for this signature in database
GPG Key ID: 4AEE18F83AFDEB23
5 changed files with 235 additions and 0 deletions

View File

@ -0,0 +1,114 @@
# Board - IFlightF4_TWIN_G
> **IFlightF4_TWIN_G : Real Twin Gyroscopes.**
>
> **This Flight Controller can operate simultaneously with real dual gyroscopes to provide better flight performance for FPV player.**
## Features
* Processors and Sensors
* *MCU:* STM32F405RGT6
* IMU_1: ICM20689(0 deg)
* IMU_2: ICM20689(90 deg)
* *OSD:* BetaFlight OSD (AT7456E connected via SPI2)
* Blackbox: FLASH M25Q256 (connected via SPI3)
* 4 Dshot outputs
* USB VCP and boot select button on board (for DFU)
* Serial LED interface(LED_STRIP)
* VBAT / CURR sensors input
* Suppose IRC Tramp / Smart audio / FPV Camera Control / FPORT/telemetry
* Supports SBus, Spektrum1024/2048, PPM. No external inverters required (built-in).
## Photos
![IFlightF4_TWIN_G](images/IFlightF4_TWIN_G.png)
![IFlightF4_TWIN_G-Botton](images/IFlightF4_TWIN_G-Botton.png)
![IFlightF4_TWIN_G-Top](images/IFlightF4_TWIN_G-Top.png)
## Pinout
### All uarts have pad on board
| Value | Identifier | RX | TX | Notes |
| :---: | :--------: | :--: | :--: | :------: |
| 1 | USART1 | PA10 | PA9 | |
| 2 | USART2 | PA3 | PA2 | Rx input |
| 3 | USART3 | PB11 | PB10 | |
| 6 | USART6 | PC7 | PC6 | |
### Buzzer/LED output
| Value | Identifier | function | pin | Notes |
| :---: | :--------: | :------: | :--: | :---: |
| 1 | LED0 | LED | PB5 | |
| 2 | BEEPER | BEEP | PB4 | |
### VBAT input, Current input, Analog RSSI input
| Value | Identifier | function | pin | Notes |
| :---: | :--------: | :------: | :--: | :---: |
| 1 | ADC1 | VBAT | PC2 | |
| 2 | ADC1 | CURRENT | PC1 | |
### PWM Input & PWM Output
| Value | Identifier | function | pin | Notes |
| :---: | :--------: | :---------: | :--: | :---: |
| 1 | TIM9_CH2 | PPM | PA3 | |
| 2 | TIM3_CH3 | Motor1 | PB0 | |
| 3 | TIM3_CH4 | Motor2 | PB1 | |
| 4 | TIM8_CH4 | Motor5 | PC9 | |
| 5 | TIM8_CH3 | Motor6 | PC8 | |
| 6 | TIM4_CH1 | LED STRIP | PB6 | |
| 7 | TIM5_CH1 | CAM Control | PA0 | |
### Gyro & ACC ICM20689
| Value | Identifier | function | pin | Notes |
| :---: | :--------: | :------: | :--: | :------------: |
| 1 | SPI1 | SCK | PA5 | ICM20689 |
| 2 | SPI1 | MISO | PA6 | ICM20689 |
| 3 | SPI1 | MOSI | PA7 | ICM20689 |
| 4 | IO | CS1 | PA4 | ICM20689_A_CS |
| 5 | IO | CS2 | PC3 | ICM20689_B_CS |
| 6 | IO | INT1 | PC4 | ICM20689_A_INT |
| 7 | IO | INT2 | PA8 | ICM20689_B_INT |
### OSD MAX7456
| Value | Identifier | function | pin | Notes |
| :---: | :--------: | :------: | :--: | :---: |
| 1 | SPI2 | SCK | PB13 | |
| 2 | SPI2 | MISO | PB14 | |
| 3 | SPI2 | MOSI | PB15 | |
| 4 | SPI2 | CS | PB12 | |
### FLash Blackbox
| Value | Identifier | function | pin | Notes |
| :---: | :--------: | :------: | :--: | :---: |
| 1 | SPI3 | SCK | PC10 | |
| 2 | SPI3 | MISO | PC11 | |
| 3 | SPI3 | MOSI | PC12 | |
| 4 | SPI3 | CS | PA15 | |
### SWD
| Pin | Function | Notes |
| :--: | :------: | :---: |
| 1 | SWCLK | PAD |
| 2 | Ground | PAD |
| 3 | SWDIO | PAD |
| 4 | 3V3 | PAD |

Binary file not shown.

After

Width:  |  Height:  |  Size: 1.4 MiB

Binary file not shown.

After

Width:  |  Height:  |  Size: 1.8 MiB

Binary file not shown.

After

Width:  |  Height:  |  Size: 1.5 MiB

View File

@ -0,0 +1,121 @@
# Betaflight / STM32F405 (S405) 4.0.0 Mar 14 2019 / 11:45:26 (360afd96d) MSP API: 1.41
board_name IFF4_TWIN_G
manufacturer_id IFRC
# resources
resource BEEPER 1 B04
resource MOTOR 1 B00
resource MOTOR 2 B01
resource MOTOR 3 C09
resource MOTOR 4 C08
resource PPM 1 A03
resource LED_STRIP 1 B06
resource SERIAL_TX 1 A09
resource SERIAL_TX 2 A02
resource SERIAL_TX 3 B10
resource SERIAL_TX 4 A00
resource SERIAL_TX 6 C06
resource SERIAL_RX 1 A10
resource SERIAL_RX 2 A03
resource SERIAL_RX 3 B11
resource SERIAL_RX 4 A01
resource SERIAL_RX 6 C07
resource INVERTER 2 C13
resource I2C_SCL 1 B08
resource I2C_SDA 1 B09
resource LED 1 B05
resource SPI_SCK 1 A05
resource SPI_SCK 2 B13
resource SPI_SCK 3 C10
resource SPI_MISO 1 A06
resource SPI_MISO 2 B14
resource SPI_MISO 3 C11
resource SPI_MOSI 1 A07
resource SPI_MOSI 2 B15
resource SPI_MOSI 3 C12
resource CAMERA_CONTROL 1 A00
resource ADC_BATT 1 C02
resource ADC_CURR 1 C01
resource PINIO 1 C14
resource PINIO 2 C15
resource FLASH_CS 1 A15
resource OSD_CS 1 B12
resource GYRO_EXTI 1 C04
resource GYRO_EXTI 2 A08
resource GYRO_CS 1 A04
resource GYRO_CS 2 C03
resource USB_DETECT 1 C05
# timer
timer A03 0
timer B00 1
timer B01 1
timer C09 1
timer C08 1
timer B06 0
timer A00 0
# dma
dma ADC 1 1
# ADC 1: DMA2 Stream 4 Channel 0
dma pin B00 0
# pin B00: DMA1 Stream 7 Channel 5
dma pin B01 0
# pin B01: DMA1 Stream 2 Channel 5
dma pin C09 0
# pin C09: DMA2 Stream 7 Channel 7
dma pin C08 0
# pin C08: DMA2 Stream 2 Channel 0
dma pin B06 0
# pin B06: DMA1 Stream 0 Channel 2
dma pin A00 0
# pin A00: DMA1 Stream 5 Channel 3
# feature
feature -RX_PARALLEL_PWM
feature RX_SERIAL
feature TELEMETRY
feature LED_STRIP
feature DISPLAY
feature OSD
# serial
serial 1 64 115200 57600 0 115200
# master
set gyro_to_use = BOTH
set mag_hardware = NONE
set baro_hardware = NONE
set serialrx_provider = SBUS
set blackbox_device = SPIFLASH
set dshot_burst = ON
set motor_pwm_protocol = DSHOT600
set current_meter = ADC
set battery_meter = ADC
set pid_process_denom = 1
set osd_warn_core_temp = OFF
set osd_warn_rc_smoothing = OFF
set osd_warn_fail_safe = OFF
set osd_warn_launch_control = OFF
set osd_warn_no_gps_rescue = OFF
set osd_warn_gps_rescue_disabled = OFF
set osd_vbat_pos = 2401
set osd_rssi_pos = 2106
set osd_vtx_channel_pos = 2424
set osd_crosshairs_pos = 2253
set osd_ah_sbar_pos = 2254
set osd_ah_pos = 2126
set osd_compass_bar_pos = 106
set osd_warnings_pos = 2377
set system_hse_mhz = 8
set vcd_video_system = NTSC
set max7456_spi_bus = 2
set dashboard_i2c_bus = 1
set pinio_box = 40,41,255,255
set flash_spi_bus = 3
set gyro_1_bustype = SPI
set gyro_1_spibus = 1
set gyro_1_sensor_align = CW0
set gyro_2_spibus = 1
set gyro_2_sensor_align = CW90