Merge pull request #8097 from blckmn/VIVAF4AIO

VIVAF4AIO
This commit is contained in:
J Blackman 2019-04-27 13:10:24 +10:00 committed by GitHub
commit 078b25c565
No known key found for this signature in database
GPG Key ID: 4AEE18F83AFDEB23
5 changed files with 199 additions and 11 deletions

View File

@ -0,0 +1,77 @@
# Board - VIVAF4AIO
The VIVAF4AIO described here:
https://team-blacksheep.com/products/prod:viva_f4_fc
* STM32 F4 Processor
* ICM20602 Gyro, BMP280 Baro
* 5V 3A, 3.3V 0.5A BEC
* 2-6S battery input
* Betaflight OSD
* 16MB BlackBox memory
* Plug & Play connector for VivaFPV 4in1 ESC with telemetry & current sensor
* Plug & Play connector for TBS Unify Pro HV (7pin)
* Direct solder compatible with TBS Crossfire Nano & TBS Crossfire Nano Diversity Rx
* 5X UART (UART1 = RX, UART2 = VTX)
* Currentsensor & Camera Control included
* 30.5x30.5 mounting holes
* USB-Micro socket for firmware upgrades
### All uarts have pad on board
| Value | Identifier | RX | TX | Notes |
| ----- | ------------ | -----| -----| ------------------------------------------------------------------------------------------- |
| 1 | USART1 | PB7 | PA9 | PB7 FOR SBUS IN(inverter build in) |
| 2 | USART2 | PA3 | PA2 | PAD USE FOR TRAMP/smart audio |
| 3 | USART3 | PB11 | PB10| USE FOR GPS |
| 4 | USART4 | PA1 | PA0 | PA0 FOR RSSI/FPORT/TEL etc |
| 5 | USART5 | PD2 | PC12| PAD |
### I2C with GPS port together, also utilised for BARO or compass etc
| Value | Identifier | function | pin | Notes |
| ----- | ------------ | ---------| -------| ------------------------------------------------------------------------------------- |
| 1 | I2C1 | SDA | PB9 | with GPS outlet
| 2 | I2C1 | SCL | PB8 | with GPS outlet
### Buzzer/LED output
| Value | Identifier | function | pin | Notes |
| ----- | ------------ | ---------| -------| ------------------------------------------------------------------------------------- |
| 1 | LED0 | LED | PC14 |
| 2 | BEEPER | BEE | PC13 |
### 6 Outputs, 1 PPM input
| Value | Identifier | function | pin | Notes |
| ----- | ------------ | ----------| ------| ------------------------------------------------------------------------------------- |
| 1 | TIM12_CH2 | PPM | PB15 | PPM
| 2 | TIM3_CH3 | OUPUT1 | PB0 | DMA1_Stream7
| 3 | TIM8_CH1 | OUPUT2 | PC6 | DMA2_Stream2
| 4 | TIM1_CH3 | OUPUT3 | PA10 | DMA2_Stream6
| 5 | TIM1_CH1 | OUPUT4 | PA8 | DMA2_Stream1
| 6 | TIM8_CH3 | OUPUT5 | PC8 | DMA2_Stream4
| 7 | TIM3_CH4 | OUPUT6 | PB1 | DMA1_Stream2
| 10 | TIM4_CH1 | PWM | PB6 | DMA1_Stream0 LED_STRIP
| 11 | TIM2_CH1 | PWM | PA5 | FPV Camera Control(FCAM)
### Gyro & ACC ,suppose ICM20602/MPU6000
| Value | Identifier | function | pin | Notes |
| ----- | ------------ | ---------| -------| ------------------------------------------------------------------------------------- |
| 1 | SPI1 | SCK | PB3 |
| 2 | SPI1 | MISO | PA6 |
| 3 | SPI1 | MOSI | PA7 |
| 4 | SPI1 | CS | PC4 |
### OSD MAX7456
| Value | Identifier | function | pin | Notes |
| ----- | ------------ | ---------| -------| ------------------------------------------------------------------------------------- |
| 1 | SPI3 | SCK | PC10 |
| 2 | SPI3 | MISO | PC11 |
| 3 | SPI3 | MOSI | PB5 |
| 4 | SPI3 | CS | PA15 |
### 16Mbyte flash
| Value | Identifier | function | pin | Notes |
| ----- | ------------ | ---------| -------| ------------------------------------------------------------------------------------- |
| 1 | SPI2 | SCK | PB13 |
| 2 | SPI2 | MISO | PB14 |
| 3 | SPI2 | MOSI | PC3 |
| 4 | SPI2 | CS | PB12 |

View File

@ -0,0 +1 @@
# VIVAF4AIO has motors 7 and 8 defined.

View File

@ -37,8 +37,10 @@ const timerHardware_t timerHardware[USABLE_TIMER_CHANNEL_COUNT] = {
DEF_TIM(TIM8, CH3, PC8, TIM_USE_MOTOR, 0, 0), // S5 (2,4) (2.2)
DEF_TIM(TIM3, CH4, PB1, TIM_USE_MOTOR, 0, 0), // S6 (1,2)
#if !defined(VIVAF4AIO)
DEF_TIM(TIM3, CH2, PC7, TIM_USE_MOTOR, 0, 0), // S7 (1,5)
DEF_TIM(TIM8, CH4, PC9, TIM_USE_MOTOR, 0, 0), // S8 (2,7)
#endif
DEF_TIM(TIM4, CH1, PB6, TIM_USE_LED, 0, 0), // LED STRIP(1,0)

View File

@ -20,8 +20,13 @@
#pragma once
#if defined(VIVAF4AIO)
# define TARGET_BOARD_IDENTIFIER "VIVA"
# define USBD_PRODUCT_STRING "VIVAF405AIO"
#else
# define TARGET_BOARD_IDENTIFIER "DLF4"
# define USBD_PRODUCT_STRING "DALRCF405"
#endif
//----------------------------------------
//LED & BEE-------------------------------
@ -48,12 +53,18 @@
#define USE_ACC
#define GYRO_1_CS_PIN PA4
#define GYRO_1_SPI_INSTANCE SPI1
#define GYRO_1_ALIGN CW90_DEG
#define ACC_1_ALIGN CW90_DEG
#if defined(VIVAF4AIO)
//------ICM20602
# define USE_GYRO_SPI_ICM20602
# define USE_ACC_SPI_ICM20602
# define GYRO_1_ALIGN CW0_DEG
#else
//------ICM20689
# define USE_GYRO_SPI_ICM20689
# define USE_ACC_SPI_ICM20689
# define GYRO_1_ALIGN CW90_DEG
#endif
//------MPU6000
#define USE_GYRO_SPI_MPU6000
@ -151,9 +162,9 @@
#define TARGET_IO_PORTC 0xffff
#define TARGET_IO_PORTD (BIT(2))
#if defined(VIVAF4AIO)
# define USABLE_TIMER_CHANNEL_COUNT 9
#else
# define USABLE_TIMER_CHANNEL_COUNT 11
#endif
#define USED_TIMERS (TIM_N(1)|TIM_N(2)|TIM_N(3)|TIM_N(4)|TIM_N(8)|TIM_N(12))

View File

@ -0,0 +1,97 @@
# Betaflight / STM32F405 (S405) 4.0.0 Mar 7 2019 / 06:40:55 (fee4ee5e0) MSP API: 1.41
board_name VIVAF4AIO
manufacturer_id VIVA
# resources
resource BEEPER 1 C13
resource MOTOR 1 B00
resource MOTOR 2 C06
resource MOTOR 3 A10
resource MOTOR 4 A08
resource MOTOR 5 C08
resource MOTOR 6 B01
resource PPM 1 B15
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 5 C12
resource SERIAL_RX 1 B07
resource SERIAL_RX 2 A03
resource SERIAL_RX 3 B11
resource SERIAL_RX 4 A01
resource SERIAL_RX 5 D02
resource I2C_SCL 1 B08
resource I2C_SDA 1 B09
resource LED 1 C14
resource SPI_SCK 1 B03
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 C03
resource SPI_MOSI 3 B05
resource ESCSERIAL 1 A03
resource CAMERA_CONTROL 1 A05
resource ADC_BATT 1 C02
resource ADC_RSSI 1 C00
resource ADC_CURR 1 C01
resource FLASH_CS 1 B12
resource OSD_CS 1 A15
resource GYRO_EXTI 1 C04
resource GYRO_CS 1 A04
# timer
timer B15 2
timer B00 1
timer C06 1
timer A10 0
timer A08 0
timer C08 1
timer B01 1
timer B06 0
timer A05 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 C06 0
# pin C06: DMA2 Stream 2 Channel 0
dma pin A10 0
# pin A10: DMA2 Stream 6 Channel 0
dma pin A08 1
# pin A08: DMA2 Stream 1 Channel 6
dma pin C08 0
# pin C08: DMA2 Stream 2 Channel 0
dma pin B01 0
# pin B01: DMA1 Stream 2 Channel 5
dma pin B06 0
# pin B06: DMA1 Stream 0 Channel 2
dma pin A05 0
# pin A05: DMA1 Stream 5 Channel 3
# master
set mag_bustype = I2C
set mag_i2c_device = 1
set baro_bustype = I2C
set baro_i2c_device = 1
set adc_device = 1
set current_meter = ADC
set battery_meter = ADC
set beeper_inversion = ON
set beeper_od = OFF
set system_hse_mhz = 8
set max7456_clock = DEFAULT
set max7456_spi_bus = 3
set dashboard_i2c_bus = 1
set flash_spi_bus = 2
set gyro_1_bustype = SPI
set gyro_1_spibus = 1
set gyro_1_sensor_align = CW0