SYNERGYF4 updated target for 4.0 and unified targets

Updated the existing 3.5.x maintenance branch SYNERGYF4 target to be 4.0 and unified target compatible.

Including:
- Legacy target for 4.0
- Unified target for future releases
- Documentation
This commit is contained in:
Lexio 2019-04-02 12:42:47 +02:00
parent 88665a6784
commit 96c21e846d
9 changed files with 224 additions and 0 deletions

View File

@ -0,0 +1,49 @@
### Specifications
- Processor: STM32F405 (F4 processor)
- Gyro: MPU6000
- Loop: 8k/8k
- Input: 2-6S (Max 28V)
- Regulator: Filtered 5V 3A
- Receiver: 3.3V or 5V selectable. Inverted and non-inverted selectable receiver input
- Connectors: 8 pin JST-SH main connector. 2x 3 pin JST-SH Addressable LED connectors (mirrored output)
- Telemetry: Current Sensor and ESC Telemetry Input
- Blackbox: 128Mbit flash (16Megabytes)
- Motor: 4 pwm motor outputs with D-Shot and Multishot support
- Mounting: M3 30.5x30.5mm holes with soft mounting
- Dimensions: 37x37mm
- Weight: 7.5g
- Camera: Filtered 5V output
### Features
- Direct mounting for Unify Pro (5V), Unify Nano, Unify Pro Nano32 (Nano VTXs use adapter board included)
- Direct mounting for TBS CrossFire Nano RX, TBS CrossFire Nano Diversity RX, FR Sky XM+, and FR Sky R9m Mini (R9m Mini Adapter Included From Tiny's LEDs)
- Header holes for direct receiver installation.
- Built in camera control via single wire (analog only)
- Built in BetaFlight OSD
- Buzzer: Dedicated pads for 5V (100mA max) buzzers
- Onboard addressable LED
- Built in Tinys LEDs RealPit VTX power switch (selectable between ON-OFF-Remote)
- Receiver can be powered on via USB (VTX stays off)
- SmartAudio: Selectable between internal (FC controlled) and external (receiver).
### UART info
- UART1: Receiver (FrSky, Spektrum, Crossfire, etc)
- UART3: SmartAudio (or any other desired output if SmartAudio is selected to pull signal from the “external” pad, designated RX SA on the top of the FC)
- UART6: ESC Telemetry (if applicable).
### Top
![Top](images/SYNERGYF4-top.png)
### Bottom
![Bottom](images/SYNERGYF4-bottom.png)
### Photo
![Main](images/SYNERGYF4-main.jpg)
`*** The flight controller does not include a receiver or VTX. The picture is for illustration only!`
### Installation
- Video: https://www.facebook.com/kevinslee106/videos/10156338569116234
### Where to get
- WhitenoiseFPV: https://whitenoisefpv.com/products/synergyf4
- Tiny's LEDs: https://tinysleds.com/products/synergy-f4-flight-controller

Binary file not shown.

After

Width:  |  Height:  |  Size: 67 KiB

Binary file not shown.

After

Width:  |  Height:  |  Size: 39 KiB

Binary file not shown.

After

Width:  |  Height:  |  Size: 68 KiB

View File

@ -0,0 +1 @@
#SYNERGYF4

View File

@ -32,6 +32,23 @@
#include "pg/max7456.h" #include "pg/max7456.h"
#include "pg/pg.h" #include "pg/pg.h"
#ifdef SYNERGYF4
#include "io/vtx.h"
#include "io/ledstrip.h"
#include "fc/config.h"
#include "pg/piniobox.h"
#include "common/axis.h"
#include "sensors/barometer.h"
#include "sensors/compass.h"
#include "sensors/gyro.h"
#include "flight/mixer.h"
#include "flight/pid.h"
#include "drivers/pwm_output.h"
static targetSerialPortFunction_t targetSerialPortFunction[] = {
{ SERIAL_PORT_USART1, FUNCTION_RX_SERIAL },
{ SERIAL_PORT_USART3, FUNCTION_VTX_SMARTAUDIO },
};
#endif
#ifdef EXUAVF4PRO #ifdef EXUAVF4PRO
static targetSerialPortFunction_t targetSerialPortFunction[] = { static targetSerialPortFunction_t targetSerialPortFunction[] = {
{ SERIAL_PORT_USART1, FUNCTION_TELEMETRY_SMARTPORT }, { SERIAL_PORT_USART1, FUNCTION_TELEMETRY_SMARTPORT },
@ -51,5 +68,14 @@ void targetConfiguration(void)
#ifdef EXUAVF4PRO #ifdef EXUAVF4PRO
targetSerialPortFunctionConfig(targetSerialPortFunction, ARRAYLEN(targetSerialPortFunction)); targetSerialPortFunctionConfig(targetSerialPortFunction, ARRAYLEN(targetSerialPortFunction));
#endif #endif
#ifdef SYNERGYF4
pinioBoxConfigMutable()->permanentId[0] = 39;
vtxSettingsConfigMutable()->pitModeFreq = 0;
ledStripStatusModeConfigMutable()->ledConfigs[0] = DEFINE_LED(0, 0, 0, 0, LF(COLOR), LO(VTX), 0);
targetSerialPortFunctionConfig(targetSerialPortFunction, ARRAYLEN(targetSerialPortFunction));
motorConfigMutable()->dev.motorPwmProtocol = PWM_TYPE_DSHOT600;
gyroConfigMutable()->gyro_sync_denom = 1; // 8kHz gyro
pidConfigMutable()->pid_process_denom = 1; // 8kHz PID
#endif
} }
#endif #endif

View File

@ -50,10 +50,16 @@ const timerHardware_t timerHardware[USABLE_TIMER_CHANNEL_COUNT] = {
#if defined(OMNIBUSF4SD) || defined(EXUAVF4PRO) #if defined(OMNIBUSF4SD) || defined(EXUAVF4PRO)
DEF_TIM(TIM5, CH2, PA1, TIM_USE_MOTOR, 0, 0), // S5_OUT DEF_TIM(TIM5, CH2, PA1, TIM_USE_MOTOR, 0, 0), // S5_OUT
DEF_TIM(TIM4, CH1, PB6, TIM_USE_LED, 0, 0), // LED strip for F4 V2 / F4-Pro-0X and later (RCD_CS for F4) DEF_TIM(TIM4, CH1, PB6, TIM_USE_LED, 0, 0), // LED strip for F4 V2 / F4-Pro-0X and later (RCD_CS for F4)
#elif defined(SYNERGYF4)
DEF_TIM(TIM5, CH2, PA1, TIM_USE_LED, 0, 0), // LED strip
#else #else
DEF_TIM(TIM5, CH2, PA1, TIM_USE_MOTOR | TIM_USE_LED, 0, 0), // S5_OUT DEF_TIM(TIM5, CH2, PA1, TIM_USE_MOTOR | TIM_USE_LED, 0, 0), // S5_OUT
#endif #endif
#if defined(SYNERGYF4)
DEF_TIM(TIM1, CH1, PA8, TIM_USE_CAMERA_CONTROL, 0, 0), // CAM_CTL
#else
DEF_TIM(TIM1, CH1, PA8, TIM_USE_MOTOR, 0, 0), // S6_OUT DEF_TIM(TIM1, CH1, PA8, TIM_USE_MOTOR, 0, 0), // S6_OUT
#endif
DEF_TIM(TIM1, CH2, PA9, TIM_USE_NONE, 0, 0), // UART1_TX DEF_TIM(TIM1, CH2, PA9, TIM_USE_NONE, 0, 0), // UART1_TX
DEF_TIM(TIM1, CH3, PA10, TIM_USE_NONE, 0, 0), // UART1_RX DEF_TIM(TIM1, CH3, PA10, TIM_USE_NONE, 0, 0), // UART1_RX
}; };

View File

@ -32,6 +32,9 @@
#define TARGET_BOARD_IDENTIFIER "XRF4" #define TARGET_BOARD_IDENTIFIER "XRF4"
#elif defined(EXUAVF4PRO) #elif defined(EXUAVF4PRO)
#define TARGET_BOARD_IDENTIFIER "EXF4" #define TARGET_BOARD_IDENTIFIER "EXF4"
#elif defined(SYNERGYF4)
#define TARGET_BOARD_IDENTIFIER "SYN4"
#define TARGET_MANUFACTURER_IDENTIFIER "KLEE"
#else #else
#define TARGET_BOARD_IDENTIFIER "OBF4" #define TARGET_BOARD_IDENTIFIER "OBF4"
// Example of a manufacturer ID to be persisted as part of the config: // Example of a manufacturer ID to be persisted as part of the config:
@ -47,6 +50,8 @@
#define USBD_PRODUCT_STRING "XRACERF4" #define USBD_PRODUCT_STRING "XRACERF4"
#elif defined(EXUAVF4PRO) #elif defined(EXUAVF4PRO)
#define USBD_PRODUCT_STRING "ExuavF4Pro" #define USBD_PRODUCT_STRING "ExuavF4Pro"
#elif defined(SYNERGYF4)
#define USBD_PRODUCT_STRING "SynergyF4"
#else #else
#define USBD_PRODUCT_STRING "OmnibusF4" #define USBD_PRODUCT_STRING "OmnibusF4"
#endif #endif
@ -93,6 +98,9 @@
#elif defined(XRACERF4) || defined(EXUAVF4PRO) #elif defined(XRACERF4) || defined(EXUAVF4PRO)
#define GYRO_1_ALIGN CW90_DEG #define GYRO_1_ALIGN CW90_DEG
#define ACC_1_ALIGN CW90_DEG #define ACC_1_ALIGN CW90_DEG
#elif defined(SYNERGYF4)
#define GYRO_1_ALIGN CW0_DEG_FLIP
#define ACC_1_ALIGN CW0_DEG_FLIP
#else #else
#define GYRO_1_ALIGN CW180_DEG #define GYRO_1_ALIGN CW180_DEG
#define ACC_1_ALIGN CW180_DEG #define ACC_1_ALIGN CW180_DEG
@ -113,12 +121,15 @@
#define GYRO_2_EXTI_PIN NONE #define GYRO_2_EXTI_PIN NONE
#define ACC_2_ALIGN ALIGN_DEFAULT #define ACC_2_ALIGN ALIGN_DEFAULT
#if !defined(SYNERGYF4) //No mag sensor on SYNERGYF4
#define USE_MAG #define USE_MAG
#define USE_MAG_HMC5883 #define USE_MAG_HMC5883
#define USE_MAG_QMC5883 #define USE_MAG_QMC5883
#define USE_MAG_LIS3MDL #define USE_MAG_LIS3MDL
#define MAG_HMC5883_ALIGN CW90_DEG #define MAG_HMC5883_ALIGN CW90_DEG
#endif
#if !defined(SYNERGYF4) //No baro sensor on SYNERGYF4
#define USE_BARO #define USE_BARO
#if defined(OMNIBUSF4SD) #if defined(OMNIBUSF4SD)
#define USE_BARO_SPI_BMP280 #define USE_BARO_SPI_BMP280
@ -135,6 +146,7 @@
#else #else
#define DEFAULT_BARO_BMP280 #define DEFAULT_BARO_BMP280
#endif #endif
#endif
#define USE_MAX7456 #define USE_MAX7456
#define MAX7456_SPI_INSTANCE SPI3 #define MAX7456_SPI_INSTANCE SPI3
@ -278,7 +290,11 @@
#define RANGEFINDER_HCSR04_ECHO_PIN PA8 #define RANGEFINDER_HCSR04_ECHO_PIN PA8
#define USE_RANGEFINDER_TF #define USE_RANGEFINDER_TF
#if defined(SYNERGYF4)
#define DEFAULT_FEATURES (FEATURE_LED_STRIP | FEATURE_OSD | FEATURE_AIRMODE)
#else
#define DEFAULT_FEATURES (FEATURE_OSD) #define DEFAULT_FEATURES (FEATURE_OSD)
#endif
#define DEFAULT_VOLTAGE_METER_SOURCE VOLTAGE_METER_ADC #define DEFAULT_VOLTAGE_METER_SOURCE VOLTAGE_METER_ADC
#define DEFAULT_CURRENT_METER_SOURCE CURRENT_METER_ADC #define DEFAULT_CURRENT_METER_SOURCE CURRENT_METER_ADC
@ -295,3 +311,8 @@
#define USABLE_TIMER_CHANNEL_COUNT 14 #define USABLE_TIMER_CHANNEL_COUNT 14
#define USED_TIMERS ( TIM_N(1) | TIM_N(2) | TIM_N(3) | TIM_N(5) | TIM_N(8) | TIM_N(12) ) #define USED_TIMERS ( TIM_N(1) | TIM_N(2) | TIM_N(3) | TIM_N(5) | TIM_N(8) | TIM_N(12) )
#endif #endif
#if defined(SYNERGYF4)
#define USE_PINIO
#define PINIO1_PIN PB15 // VTX power switcher
#define USE_PINIOBOX
#endif

View File

@ -0,0 +1,121 @@
# Betaflight / STM32F405 (S405) 4.0.0 Apr 1 2019 / 19:06:47 (88665a678) MSP API: 1.41
board_name SYNERGYF4
manufacturer_id KLEE
# resources
resource BEEPER 1 B04
resource MOTOR 1 B00
resource MOTOR 2 B01
resource MOTOR 3 A03
resource MOTOR 4 A02
resource PPM 1 B14
resource PWM 1 B14
resource PWM 2 B15
resource PWM 3 C06
resource PWM 4 C07
resource PWM 5 C08
resource PWM 6 C09
resource SONAR_TRIGGER 1 A01
resource SONAR_ECHO 1 A08
resource LED_STRIP 1 A01
resource SERIAL_TX 1 A09
resource SERIAL_TX 3 B10
resource SERIAL_TX 6 C06
resource SERIAL_RX 1 A10
resource SERIAL_RX 3 B11
resource SERIAL_RX 6 C07
resource INVERTER 1 C00
resource LED 1 B05
resource SPI_SCK 1 A05
resource SPI_SCK 3 C10
resource SPI_MISO 1 A06
resource SPI_MISO 3 C11
resource SPI_MOSI 1 A07
resource SPI_MOSI 3 C12
resource ESCSERIAL 1 B14
resource CAMERA_CONTROL 1 A08
resource ADC_BATT 1 C02
resource ADC_RSSI 1 A00
resource ADC_CURR 1 C01
resource PINIO 1 B15
resource FLASH_CS 1 B03
resource OSD_CS 1 A15
resource GYRO_EXTI 1 C04
resource GYRO_CS 1 A04
resource USB_DETECT 1 C05
# timer
timer B14 2
timer B15 2
timer C06 1
timer C07 1
timer C08 1
timer C09 1
timer B00 1
timer B01 1
timer A03 0
timer A02 0
timer A01 1
timer A08 0
timer A09 0
timer A10 0
# dma
dma ADC 2 1
# ADC 2: DMA2 Stream 3 Channel 1
dma pin C06 0
# pin C06: DMA2 Stream 2 Channel 0
dma pin C07 0
# pin C07: DMA2 Stream 2 Channel 0
dma pin C08 0
# pin C08: DMA2 Stream 2 Channel 0
dma pin C09 0
# pin C09: DMA2 Stream 7 Channel 7
dma pin B00 0
# pin B00: DMA1 Stream 7 Channel 5
dma pin B01 0
# pin B01: DMA1 Stream 2 Channel 5
dma pin A03 1
# pin A03: DMA1 Stream 6 Channel 3
dma pin A02 0
# pin A02: DMA1 Stream 1 Channel 3
dma pin A01 0
# pin A01: DMA1 Stream 4 Channel 6
dma pin A08 0
# pin A08: DMA2 Stream 6 Channel 0
dma pin A09 0
# pin A09: DMA2 Stream 6 Channel 0
dma pin A10 0
# pin A10: DMA2 Stream 6 Channel 0
# feature
feature LED_STRIP
feature OSD
feature AIRMODE
# serial
serial 0 64 115200 57600 0 115200
serial 2 2048 115200 57600 0 115200
# led
led 0 0,0::CV:0
# master
set adc_device = 2
set blackbox_device = SPIFLASH
set motor_pwm_protocol = DSHOT600
set current_meter = ADC
set battery_meter = ADC
set beeper_inversion = ON
set beeper_od = OFF
set pid_process_denom = 1
set system_hse_mhz = 8
set max7456_spi_bus = 3
set dashboard_i2c_bus = 2
set pinio_box = 39,255,255,255
set flash_spi_bus = 3
set gyro_1_bustype = SPI
set gyro_1_spibus = 1
set gyro_1_sensor_align = CW0FLIP
set gyro_2_spibus = 1