JHEMCU GSF405A - a 3.3g 1-2S F405 AIO FC w/5A ESCs, BMP280, BB, and 2.4G ELRS!

JHEMCU has released a new 1-2S AIO Whoop board using a F405 MCU that should be Ardupilot compatible. I have one and am planning a small 1S Arducopter build for it. To my knowledge, this is the first complete 1S F405 board and I’m excited for the possibilities this opens up for <3" Arducopters, micro Arduplanes, and tiny Ardurovers!

Specs:

Flight control parameters

  • MCU: STM32F405OG6
  • Gyroscope/Accelerometer: MPU6000
  • OSD: AT7456E
  • Barometer: BMP280
  • Black box: 8MB
  • I2C: Support
  • BEC: 5V
  • UART: UART1 (ELRS), UART2 (external RC), UART3, UART4, UART6
  • USB: micro usb
  • Size: 25.5*25.5MM M2
  • Receiver: ELRS (CRSF), TBS (CRSF), SBUS, IBUS, DSM2, DSMX
  • Support programmable LED such as WS2812
  • Support buzzer
  • Built-in voltage and current sensors
  • Weight: 3.3 grams

ESC parameters

  • Support PWM, Oneshot125, Oneshot42, Multishot, Dshot150, Dshot300, Dshot600
  • Input voltage: 1S-2S Lipo
  • Continuous current: 5A
  • Firmware: BLHELI_S S_H_50_REV16_7.HEX
3 Likes

Here is the Betaflight config for the board:

It looks like the closest current Ardupilot target is the MambaF405US-I2C:

I’ll start working on a new target for the GSF405A board this weekend.

1 Like

I also noticed this FC which could be a good and relatively cheap solution for small sub 250 copters. Maybe @andyp1per can tell us if the ardupilot code can be adapted?

Certainly should be possble

1 Like

I’ve done a little work on creating a new target for this board. This is a WIP and untested.

Goal is to have bidirectional DShot support, DMA on USART1 (on-board ELRS, uses CRSF protocol), USART3 (for GPS), and UART6. I have a timer assigned to the LED_STRIP pin, but don’t know if TIM1_UP is sufficient for WS2812 use.

What is the correct value of HAL_STORAGE_SIZE for 8M onboard flash?

hwdef.dat:

# hw definition file for processing by chibios_pins.py
# JHEMCU GSF405A
# With F405 MCU, MPU6000 IMU and 7456 series OSD
# Based on Mamba F405 from jeanphilippehell
@ thanks to betaflight for pin information

MCU STM32F4xx STM32F405xx

# board ID for firmware load
APJ_BOARD_ID 1060

# crystal frequency
OSCILLATOR_HZ 8000000

# board voltage
STM32_VDD 330U

define STM32_ST_USE_TIMER 4
define CH_CFG_ST_RESOLUTION 16

# order of I2C buses
I2C_ORDER I2C1

# order of UARTs (and USB)
# this order follows the labels on the board
SERIAL_ORDER OTG1 USART1 USART2 USART3 UART4 EMPTY USART6

# The pins that USB is connected on
PA11 OTG_FS_DM OTG1
PA12 OTG_FS_DP OTG1
PC5 VBUS INPUT OPENDRAIN

# USART1 (DMA) - wired to on-board ELRS receiver - need DMA for CRSF protocol
PB6 USART1_TX USART1
PA10 USART1_RX USART1

# Alt config to allow PPM on RX1
#PA10 TIM1_CH3 TIM1 RCININT PULLDOWN ALT(1)

# USART2
PD5 USART2_TX USART2 NODMA
PD6 USART2_RX USART2 NODMA

# USART3 (DMA) - Use for GPS as it is close to I2C pins. 
PB10 USART3_TX USART3
PB11 USART3_RX USART3

# UART4
PA0 UART4_TX UART4
PA1 UART4_RX UART4 NODMA

# USART6 (DMA)
PC6 USART6_TX USART6
PC7 USART6_RX USART6

# ADC
PC3 BAT_VOLT_SENS ADC1 SCALE(1)
PC0 RSSI_IN ADC1
PC2 BAT_CURR_SENS ADC1 SCALE(1)

# Motor outputs on AIO ESC
PB0 TIM3_CH3 TIM3 PWM(1) GPIO(50) 
PB1 TIM3_CH4 TIM3 PWM(2) GPIO(51) BIDIR
PA3 TIM5_CH4 TIM5 PWM(3) GPIO(52) BIDIR
PA2 TIM5_CH3 TIM5 PWM(4) GPIO(53) 


# Board LEDs
PC14 LED1 OUTPUT LOW GPIO(1)
#PC14 LED2 OUTPUT LOW GPIO(2)
define HAL_GPIO_A_LED_PIN 1
#define HAL_GPIO_B_LED_PIN 2

# Assign timer to LED_STRIP
#PA9 LED_EXT1 OUTPUT GPIO(30)
PA9 TIM1_CH2 TIM1 PWM(5) GPIO(54)

DMA_PRIORITY SPI3*
DMA_NOSHARE USART1*

# Buzzer
PC13 BUZZER OUTPUT GPIO(80) LOW
define HAL_BUZZER_PIN 80
define HAL_BUZZER_ON 1
define HAL_BUZZER_OFF 0

# I2C1
PB8 I2C1_SCL I2C1
PB9 I2C1_SDA I2C1

# SPI1 - Internal IMU
PB12 MPU6000_CS CS
PA5 SPI1_SCK SPI1
PA6 SPI1_MISO SPI1
PA7 SPI1_MOSI SPI1

# SPI2 - none
#PB13 SPI2_SCK SPI2
#PB14 SPI2_MISO SPI2
#PB15 SPI2_MOSI SPI2


# SPI3 - OSD + 8MB flash
PC10 SPI3_SCK SPI3
PC11 SPI3_MISO SPI3
PC12 SPI3_MOSI SPI3
# OSD max7456
PB14 OSD_CS CS
# Dataflash 8MB on-board
PB3 FLASH_CS CS

# SPI Device table
SPIDEV mpu6000    SPI1 DEVID1 MPU6000_CS MODE3 1*MHZ 4*MHZ
SPIDEV dataflash  SPI3 DEVID2 FLASH_CS   MODE3 32*MHZ 32*MHZ
SPIDEV osd        SPI3 DEVID3 OSD_CS MODE0 10*MHZ 10*MHZ

# One IMU rotated in yaw
IMU Invensense SPI:mpu6000 ROTATION_YAW_180

# Probe for I2C BMP280, but allow init on board variants without onboard baro too
BARO BMP280 I2C:0:0x76
define HAL_PROBE_EXTERNAL_I2C_BAROS
define HAL_BARO_ALLOW_INIT_NO_BARO

# no built-in compass, but probe the i2c bus for all possible
# external compass types
define ALLOW_ARM_NO_COMPASS
define HAL_COMPASS_DEFAULT HAL_COMPASS_NONE
define HAL_PROBE_EXTERNAL_I2C_COMPASSES
define HAL_I2C_INTERNAL_MASK 0
define HAL_COMPASS_AUTO_ROT_DEFAULT 2

# enable logging to dataflash
define HAL_LOGGING_DATAFLASH
#Is this correct for 8M onboard flash?
define HAL_STORAGE_SIZE 7168
STORAGE_FLASH_PAGE 1

# flash size
FLASH_SIZE_KB 1024
# reserve 16k for bootloader and 32k for flash storage
FLASH_RESERVE_START_KB 48

# define default battery setup
define HAL_BATT_VOLT_PIN 11
define HAL_BATT_CURR_PIN 13
define HAL_BATT_VOLT_SCALE 11
define HAL_BATT_CURR_SCALE 17

# Analog RSSI pin (also could be used as analog airspeed input)
define BOARD_RSSI_ANA_PIN 1

# Setup for OSD
define OSD_ENABLED 1
define HAL_OSD_TYPE_DEFAULT 1

# Font for OSD
ROMFS_WILDCARD libraries/AP_OSD/fonts/font*.bin

hwdef.txt (3.5 KB)

hwdef.h
hwdef.h (56.5 KB)

DMA Assignments snippet:

// auto-generated DMA mapping from dma_resolver.py
#define STM32_ADC_ADC1_DMA_STREAM      STM32_DMA_STREAM_ID(2, 4)
#define STM32_ADC_ADC1_DMA_CHAN        0
#define STM32_I2C_I2C1_RX_DMA_STREAM   STM32_DMA_STREAM_ID(1, 5)
#define STM32_I2C_I2C1_RX_DMA_CHAN     1
#define STM32_I2C_I2C1_TX_DMA_STREAM   STM32_DMA_STREAM_ID(1, 6) // shared TIM5_UP,I2C1_TX
#define STM32_I2C_I2C1_TX_DMA_CHAN     1
#define STM32_SPI_SPI1_RX_DMA_STREAM   STM32_DMA_STREAM_ID(2, 0)
#define STM32_SPI_SPI1_RX_DMA_CHAN     3
#define STM32_SPI_SPI1_TX_DMA_STREAM   STM32_DMA_STREAM_ID(2, 3)
#define STM32_SPI_SPI1_TX_DMA_CHAN     3
#define STM32_SPI_SPI3_RX_DMA_STREAM   STM32_DMA_STREAM_ID(1, 0)
#define STM32_SPI_SPI3_RX_DMA_CHAN     0
#define STM32_SPI_SPI3_TX_DMA_STREAM   STM32_DMA_STREAM_ID(1, 7)
#define STM32_SPI_SPI3_TX_DMA_CHAN     0
#define STM32_TIM_TIM1_UP_DMA_STREAM   STM32_DMA_STREAM_ID(2, 5)
#define STM32_TIM_TIM1_UP_DMA_CHAN     6
#define STM32_TIM_TIM3_CH4_DMA_STREAM  STM32_DMA_STREAM_ID(1, 2) // shared TIM3_UP,TIM3_CH4
#define STM32_TIM_TIM3_CH4_DMA_CHAN    5
#define STM32_TIM_TIM3_UP_DMA_STREAM   STM32_DMA_STREAM_ID(1, 2) // shared TIM3_UP,TIM3_CH4
#define STM32_TIM_TIM3_UP_DMA_CHAN     5
#define STM32_TIM_TIM5_CH4_DMA_STREAM  STM32_DMA_STREAM_ID(1, 3) // shared USART3_TX,TIM5_CH4
#define STM32_TIM_TIM5_CH4_DMA_CHAN    6
#define STM32_TIM_TIM5_UP_DMA_STREAM   STM32_DMA_STREAM_ID(1, 6) // shared TIM5_UP,I2C1_TX
#define STM32_TIM_TIM5_UP_DMA_CHAN     6
#define STM32_UART_UART4_TX_DMA_STREAM STM32_DMA_STREAM_ID(1, 4)
#define STM32_UART_UART4_TX_DMA_CHAN   4
#define STM32_UART_USART1_RX_DMA_STREAM STM32_DMA_STREAM_ID(2, 2)
#define STM32_UART_USART1_RX_DMA_CHAN  4
#define STM32_UART_USART1_TX_DMA_STREAM STM32_DMA_STREAM_ID(2, 7)
#define STM32_UART_USART1_TX_DMA_CHAN  4
#define STM32_UART_USART3_RX_DMA_STREAM STM32_DMA_STREAM_ID(1, 1)
#define STM32_UART_USART3_RX_DMA_CHAN  4
#define STM32_UART_USART3_TX_DMA_STREAM STM32_DMA_STREAM_ID(1, 3) // shared USART3_TX,TIM5_CH4
#define STM32_UART_USART3_TX_DMA_CHAN  4
#define STM32_UART_USART6_RX_DMA_STREAM STM32_DMA_STREAM_ID(2, 1)
#define STM32_UART_USART6_RX_DMA_CHAN  5
#define STM32_UART_USART6_TX_DMA_STREAM STM32_DMA_STREAM_ID(2, 6)
#define STM32_UART_USART6_TX_DMA_CHAN  5

// Mask of DMA streams which are shared
#define SHARED_DMA_MASK ((1U<<STM32_DMA_STREAM_ID(1,2))|(1U<<STM32_DMA_STREAM_ID(1,3))|(1U<<STM32_DMA_STREAM_ID(1,6)))


// generated UART DMA configuration lines
#define STM32_USART1_RX_DMA_CONFIG true, STM32_UART_USART1_RX_DMA_STREAM, STM32_UART_USART1_RX_DMA_CHAN
#define STM32_USART1_TX_DMA_CONFIG true, STM32_UART_USART1_TX_DMA_STREAM, STM32_UART_USART1_TX_DMA_CHAN
#define STM32_USART2_RX_DMA_CONFIG false, 0, 0
#define STM32_USART2_TX_DMA_CONFIG false, 0, 0
#define STM32_USART3_RX_DMA_CONFIG true, STM32_UART_USART3_RX_DMA_STREAM, STM32_UART_USART3_RX_DMA_CHAN
#define STM32_USART3_TX_DMA_CONFIG true, STM32_UART_USART3_TX_DMA_STREAM, STM32_UART_USART3_TX_DMA_CHAN
#define STM32_UART4_RX_DMA_CONFIG false, 0, 0
#define STM32_UART4_TX_DMA_CONFIG true, STM32_UART_UART4_TX_DMA_STREAM, STM32_UART_UART4_TX_DMA_CHAN
#define STM32_USART6_RX_DMA_CONFIG true, STM32_UART_USART6_RX_DMA_STREAM, STM32_UART_USART6_RX_DMA_CHAN
#define STM32_USART6_TX_DMA_CONFIG true, STM32_UART_USART6_TX_DMA_STREAM, STM32_UART_USART6_TX_DMA_CHAN


// generated SPI DMA configuration lines
#define STM32_SPI_SPI1_DMA_STREAMS STM32_SPI_SPI1_TX_DMA_STREAM, STM32_SPI_SPI1_RX_DMA_STREAM
#define STM32_SPI_SPI3_DMA_STREAMS STM32_SPI_SPI3_TX_DMA_STREAM, STM32_SPI_SPI3_RX_DMA_STREAM
#define HAL_PWM_COUNT 5
1 Like

Made some more progress with this, I think it’s close to ready. Accelerometer, barometer, and ELRS are tested and working. If someone wants to do a sanity check on the hwdef, I’d appreciate it!

And if anyone would like a precompiled hex to flash for testing, please let me know.

hwdef.dat

# hw definition file for processing by chibios_pins.py
# JHEMCU GSF405A by V-22
# With F405 MCU, MPU6000 IMU and MAX7456 series OSD
# Based on Mamba F405 from jeanphilippehell
@ thanks to betaflight for pin information

MCU STM32F4xx STM32F405xx

# board ID for firmware load
APJ_BOARD_ID 1060

# crystal frequency
OSCILLATOR_HZ 8000000

# board voltage
STM32_VDD 330U

# need to use timer 4 so timer 5 is available for bidir DShot
define STM32_ST_USE_TIMER 4
define CH_CFG_ST_RESOLUTION 16

# order of I2C buses
I2C_ORDER I2C1

# order of UARTs (and USB)
# this order follows the labels on the board
SERIAL_ORDER OTG1 USART1 USART2 USART3 UART4 EMPTY USART6

# The pins that USB is connected on
PA11 OTG_FS_DM OTG1
PA12 OTG_FS_DP OTG1

# USB detection
PA8 VBUS INPUT OPENDRAIN

# USART1 (DMA) - wired to on-board ELRS receiver - need DMA for CRSF protocol
PB6 USART1_TX USART1
PA10 USART1_RX USART1

# default Serial1 to ELRS RX
define HAL_SERIAL1_PROTOCOL 23
define HAL_RSSI_TYPE 3 

# Alt config to allow PPM on RX1
#PA10 TIM1_CH3 TIM1 RCININT PULLDOWN ALT(1)

# USART2
PD5 USART2_TX USART2 NODMA
PD6 USART2_RX USART2 NODMA

# USART3 (DMA) - Use for GPS as it is close to I2C pins. 
PB10 USART3_TX USART3
PB11 USART3_RX USART3

# UART4
PA0 UART4_TX UART4 NODMA
PA1 UART4_RX UART4 NODMA

# USART6 (DMA)
PC6 USART6_TX USART6
PC7 USART6_RX USART6

# analog pins
PC3 BATT_VOLTAGE_SENS ADC1 SCALE(1)
PC2 BATT_CURRENT_SENS ADC1 SCALE(1)

# RSSI analog input
PC0 RSSI_ADC_PIN ADC1 SCALE(1)
define BOARD_RSSI_ANA_PIN 1

# Motor outputs on AIO ESC
PB0 TIM3_CH3 TIM3 PWM(1) GPIO(50) 
PB1 TIM3_CH4 TIM3 PWM(2) GPIO(51) BIDIR
PA3 TIM5_CH4 TIM5 PWM(3) GPIO(52) BIDIR
PA2 TIM5_CH3 TIM5 PWM(4) GPIO(53) 


# Board LEDs
PC14 LED1 OUTPUT LOW GPIO(1)
PC15 LED2 OUTPUT LOW GPIO(2)
define HAL_GPIO_A_LED_PIN 1
define HAL_GPIO_B_LED_PIN 2

# Assign timer to LED_STRIP
#PA9 LED_EXT1 OUTPUT GPIO(30)
PA9 TIM1_CH2 TIM1 PWM(5) GPIO(54)

DMA_PRIORITY SPI1* SPI3* USART3* USART6* TIM1_CH2
DMA_NOSHARE USART1_RX TIM5_CH4

# Buzzer
PC13 BUZZER OUTPUT GPIO(80) LOW
define HAL_BUZZER_PIN 80
define HAL_BUZZER_ON 1
define HAL_BUZZER_OFF 0

# I2C1
PB8 I2C1_SCL I2C1
PB9 I2C1_SDA I2C1

# SPI1 - Internal IMU
PB12 MPU6000_CS CS
PA5 SPI1_SCK SPI1
PA6 SPI1_MISO SPI1
PA7 SPI1_MOSI SPI1

# SPI2 - none
#PB13 SPI2_SCK SPI2
#PB14 SPI2_MISO SPI2
#PB15 SPI2_MOSI SPI2


# SPI3 - OSD + 8MB flash
PC10 SPI3_SCK SPI3
PC11 SPI3_MISO SPI3
PC12 SPI3_MOSI SPI3
# OSD max7456
PB14 OSD_CS CS
# Dataflash 8MB on-board
PB3 FLASH_CS CS

# SPI Device table
SPIDEV mpu6000    SPI1 DEVID1 MPU6000_CS MODE3 1*MHZ 4*MHZ
SPIDEV dataflash  SPI3 DEVID2 FLASH_CS   MODE3 32*MHZ 32*MHZ
SPIDEV osd        SPI3 DEVID3 OSD_CS MODE0 10*MHZ 10*MHZ

# One IMU rotated in yaw
IMU Invensense SPI:mpu6000 ROTATION_YAW_90

# Probe for I2C BMP280, but allow init on board variants without onboard baro too
BARO BMP280 I2C:0:0x76
define HAL_PROBE_EXTERNAL_I2C_BAROS
#define HAL_BARO_ALLOW_INIT_NO_BARO

# no built-in compass, but probe the i2c bus for all possible
# external compass types
define ALLOW_ARM_NO_COMPASS
define HAL_COMPASS_DEFAULT HAL_COMPASS_NONE
define HAL_PROBE_EXTERNAL_I2C_COMPASSES
define HAL_I2C_INTERNAL_MASK 0
define HAL_COMPASS_AUTO_ROT_DEFAULT 2

# enable logging to dataflash
define HAL_LOGGING_DATAFLASH_ENABLED 1

define HAL_STORAGE_SIZE 15360
STORAGE_FLASH_PAGE 1

# flash size
FLASH_SIZE_KB 1024
# reserve 16k for bootloader and 32k for flash storage
FLASH_RESERVE_START_KB 48

# define default battery setup
define HAL_BATT_VOLT_PIN 11
define HAL_BATT_CURR_PIN 13
define HAL_BATT_VOLT_SCALE 11
define HAL_BATT_CURR_SCALE 17

# Setup for OSD
define OSD_ENABLED 1
define HAL_OSD_TYPE_DEFAULT 1

# Font for OSD
ROMFS_WILDCARD libraries/AP_OSD/fonts/font*.bin

hwdef.txt (3.6 KB)

hwdef-bl.dat

# hw definition file for processing by chibios_pins.py
# for JHEMCU GSF405A bootloader

# MCU class and specific type
MCU STM32F4xx STM32F405xx

# board ID for firmware load
APJ_BOARD_ID 1060

# crystal frequency
OSCILLATOR_HZ 8000000

FLASH_SIZE_KB 1024

# don't allow bootloader to use more than 16k
FLASH_USE_MAX_KB 16

# bootloader is installed at zero offset
FLASH_RESERVE_START_KB 0

# LEDs
PC14 LED1 OUTPUT LOW
PC15 LED_ACTIVITY OUTPUT LOW
define HAL_LED_ON 0

# Avoid buzzer scream
PC13 BUZZER OUTPUT LOW PULLDOWN

# the location where the bootloader will put the firmware
FLASH_BOOTLOADER_LOAD_KB 48

# board voltage
STM32_VDD 330U

# order of UARTs
SERIAL_ORDER OTG1

PA11 OTG_FS_DM OTG1
PA12 OTG_FS_DP OTG1

# Add CS pins to ensure they are high in bootloader
PB12 MPU6000_CS CS
PB14 OSD_CS CS
PB3 FLASH_CS CS

hwdef-bl.txt (821 Bytes)

Do a PR - then we can review

1 Like

PR created:

1 Like

Thanks to the devs this has now been merged with master! Please test it out if you are interested. Hopefully I will get a build together this weekend.

I also came across this new 16x16 FC/stack from JHEMCU which could be even more useful as it has 8 motor/PWM outputs:
https://www.jhemcu.com/e_productshow/?43-JHEMCU-GF16--2-4S-1616-F405-Flight-Controller-13A-4IN1-ESC-Stack-43.html

It looks like it is only available on AliExpress now, but hopefully more retailers will carry it soon. I will work on a target when I get my hands on one.

1 Like

@andyp1per Do I need to set anything in the hwdef to make sure this target compiles with CRSF Telemetry support?

Nope - as long as you haven’t used HAL_MINIMIZE_FEATURES

1 Like

The Betaflight mappings for the GF16 are available here:

I have a GF16 stack on-order that should be arriving this week. Draft hwdef.dat attached, I’ll submit a PR once I have received the board and confirmed everything is working. Should be able to support bidirectional DShot on Motor outputs 1-4, and DMA on U(S)ARTS 1, 3, and 6. PWM output 5 may be unusable if you are using DShot, as it shares a timer with M1 and M2. There are a few different ways this target can be configured depending on your requirements, but I figured the default target should support the bundled 4in1 ESC.

# hw definition file for processing by chibios_pins.py
# JHEMCU GF16 by V-22
# With F405 MCU, MPU6000 IMU and MAX7456 series OSD
# Based on Mamba F405 hwdef from jeanphilippehell
# thanks to betaflight for pin information (https://github.com/betaflight/unified-targets/blob/master/configs/default/JHEF-JHEF405PRO.config)
# Board info https://github.com/jhemcu/FC-ESC-Firmware/tree/main/GF16-F405%26ESC

MCU STM32F4xx STM32F405xx

# board ID for firmware load
APJ_BOARD_ID 1060

# crystal frequency
OSCILLATOR_HZ 8000000

# board voltage
STM32_VDD 330U

# need to use timer 2 so timer 5 is available for bidir DShot
define STM32_ST_USE_TIMER 2

# order of I2C buses
I2C_ORDER I2C1

# order of UARTs (and USB)
# this order follows the labels on the board
SERIAL_ORDER OTG1 USART1 USART2 USART3 UART4 EMPTY USART6

# The pins that USB is connected on
PA11 OTG_FS_DM OTG1
PA12 OTG_FS_DP OTG1

# USB detection
PA8 VBUS INPUT OPENDRAIN

# USART1 (DMA) - RCinput through pads TX1/RX1 or SBUS
PB6 USART1_TX USART1
PA10 USART1_RX USART1
define HAL_SERIAL1_PROTOCOL 23

# USART2
PD5 USART2_TX USART2 NODMA
PD6 USART2_RX USART2 NODMA

# USART3 (DMA) - Use for GPS as it is close to I2C pins. 
PB10 USART3_TX USART3
PB11 USART3_RX USART3

# UART4
PA0 UART4_TX UART4 NODMA
PA1 UART4_RX UART4 NODMA

# USART6 (DMA)
PC6 USART6_TX USART6
PC7 USART6_RX USART6

# analog pins
PC3 BATT_VOLTAGE_SENS ADC1 SCALE(1)
PC2 BATT_CURRENT_SENS ADC1 SCALE(1)

# RSSI analog input
PC0 RSSI_ADC_PIN ADC1 SCALE(1)
define BOARD_RSSI_ANA_PIN 12

# Motor outputs on AIO ESC
PB0 TIM3_CH3 TIM3 PWM(1) GPIO(50) 
PB1 TIM3_CH4 TIM3 PWM(2) GPIO(51) BIDIR
PA3 TIM5_CH4 TIM5 PWM(3) GPIO(52) BIDIR
PA2 TIM5_CH3 TIM5 PWM(4) GPIO(53) 
PB5 TIM3_CH2 TIM3 PWM(5) GPIO(54)
PB7 TIM4_CH2 TIM4 PWM(6) GPIO(55) NODMA
PC9 TIM8_CH4 TIM8 PWM(7) GPIO(56) NODMA
PC8 TIM8_CH3 TIM8 PWM(8) GPIO(57) NODMA

# Assign timer to LED_STRIP
PA9 TIM1_CH2 TIM1 PWM(9) GPIO(58)

DMA_PRIORITY SPI1_RX SPI3* USART3* USART6* TIM1_CH2
DMA_NOSHARE USART1* TIM5_UP

# Board LEDs
PC14 LED1 OUTPUT LOW GPIO(1)
PC15 LED2 OUTPUT LOW GPIO(2)
define HAL_GPIO_A_LED_PIN 1
define HAL_GPIO_B_LED_PIN 2

# Buzzer
PC13 BUZZER OUTPUT GPIO(80) LOW
define HAL_BUZZER_PIN 80
define HAL_BUZZER_ON 1
define HAL_BUZZER_OFF 0

# I2C1
PB8 I2C1_SCL I2C1
PB9 I2C1_SDA I2C1

# SPI1 - Internal IMU
PB12 MPU6000_CS CS
PA5 SPI1_SCK SPI1
PA6 SPI1_MISO SPI1
PA7 SPI1_MOSI SPI1
# IRQ for MPU6000
PB13 EXTI_MPU6000 INPUT

# SPI3 - OSD + 8MB flash
PC10 SPI3_SCK SPI3
PC11 SPI3_MISO SPI3
PC12 SPI3_MOSI SPI3
# OSD max7456
PB14 OSD_CS CS
# Dataflash 8MB on-board
PB3 FLASH_CS CS

# SPI Device table
SPIDEV mpu6000    SPI1 DEVID1 MPU6000_CS MODE3 1*MHZ 4*MHZ
SPIDEV dataflash  SPI3 DEVID2 FLASH_CS   MODE3 32*MHZ 32*MHZ
SPIDEV osd        SPI3 DEVID3 OSD_CS MODE0 10*MHZ 10*MHZ

# One IMU rotated in yaw
IMU Invensense SPI:mpu6000 ROTATION_YAW_90

# Probe for I2C BMP280, but allow external baro
BARO BMP280 I2C:0:0x76
define HAL_PROBE_EXTERNAL_I2C_BAROS

# no built-in compass, but probe the i2c bus for all possible
# external compass types
define ALLOW_ARM_NO_COMPASS
define HAL_COMPASS_DEFAULT HAL_COMPASS_NONE
define HAL_PROBE_EXTERNAL_I2C_COMPASSES
define HAL_I2C_INTERNAL_MASK 0
define HAL_COMPASS_AUTO_ROT_DEFAULT 2

# enable logging to dataflash
define HAL_LOGGING_DATAFLASH_ENABLED 1

define HAL_STORAGE_SIZE 15360
STORAGE_FLASH_PAGE 1

# flash size
FLASH_SIZE_KB 1024
# reserve 16k for bootloader and 32k for flash storage
FLASH_RESERVE_START_KB 48

# define default battery setup
define HAL_BATT_VOLT_PIN 11
define HAL_BATT_CURR_PIN 13
define HAL_BATT_VOLT_SCALE 11
define HAL_BATT_CURR_SCALE 17

# Setup for OSD
define OSD_ENABLED 1
define HAL_OSD_TYPE_DEFAULT 1

# Font for OSD
ROMFS_WILDCARD libraries/AP_OSD/fonts/font*.bin

# -------reduce max size of embedded params for apj_tool.py
define AP_PARAM_MAX_EMBEDDED_PARAM 1024
define HAL_WITH_DSP FALSE

# --------------------- save flash ----------------------
define HAL_BATTMON_SMBUS_ENABLE 0
define HAL_BATTMON_FUEL_ENABLE 0
define HAL_PARACHUTE_ENABLED 0
define HAL_SPRAYER_ENABLED 0
define HAL_GENERATOR_ENABLED 0
define AC_OAPATHPLANNER_ENABLED 0
define PRECISION_LANDING 0
define HAL_BARO_WIND_COMP_ENABLED 0
define GRIPPER_ENABLED 0
define HAL_HOTT_TELEM_ENABLED 0
define HAL_NMEA_OUTPUT_ENABLED 0
define HAL_BUTTON_ENABLED 0
define HAL_OREO_LED_ENABLED 0
define HAL_PICCOLO_CAN_ENABLE 0
1 Like

@CrashTestPilot Any update on the GF16? I’m looking at it as a nice compact option for a small plane.

1 Like

Just received one GF16…would be ready to test if someone can start me up.

Can someone point me to the difference between JHEMCU-GSF405A and JHEMCU-GSF405A-RX2 firmware versions?

EDIT: found it. The RX2 version is tailored to a receiver on RX2, which has DMA enabled there for that reason. The default one has a different DMA layout.

So another question. I am still unable to flash a fresh ELRS firmware onto the built-in receiver. I even tried Betaflight, but to no success (I am inexperienced in Betaflight, however).

Serial passthrough just leads to “Failed to connect to ESP8266: Timed out waiting for packet header”, with or without the RC boot button pressed at startup.

At startup, the ELRS LED behaves as if its WiFi should be up and running (e.g. first flashing slowly, then blinking quickly). However, no network is actually up.

And, of course, I cannot use the button binding feature since the existing firmware is apparently 1.x, while I am running 2.x on the transmitter.

If someone got past that point, could you please tell me what you did?

WiFi update works on mine, with the caveat that the PCB WiFi antenna is horribly designed and has extremely limited range. It needs to be within a few feet of your computer or AP to be able to connect. Try moving it closer and see if it shows up.

Also, for anyone having trouble getting the GSF405A into DFU mode to flash firmware, try holding down both boot buttons on the board before connecting to USB. I use small padded alligator clips for this as I don’t have enough hands otherwise.

Does not seem to work at all on my side, even with less than one centimeter between the PCB WiFi on the drone and the antenna on the laptop (including an external one). All my other receivers worked pretty smoothly in this regard. Maybe I am just unlucky…

On the other hand, I did not have to press both boot buttons. At least this part of this FC works well for me.

I have managed to flash the firmware by soldering an FTDI directly on the TX1/RX1 pads and on the ground. The sequence was as follows:

  • Set SERIAL1_PROTOCOL to -1 (This is in the hope that FTDI does not conflict with the FC. I had it set this way due to my earlier passthrough attempts).
  • Power off the FC.
  • Connect the FTDI to the pads (RX1, TX1, ground).
  • Power up the FC (e.g. via USB) with RC boot pin pressed.
  • Power up the FTDI.
  • Perform flashing through the configurator.
  • Power off the FTDI and the FC.
  • Disconnect the FTDI.

Few random notes:

  • Make sure you implement correctly the RX/TX connection pattern of your particular FTDI. In my case it was counter-intuitive (RX to RX, TX to TX).
  • It seems to be wise to solder thin wires to the pads first, then to connect then to the stiffer wires of FTDI. In any case, the smallish TX1/RX1 pads require some good soldering skills.

Glad you were able to get it updated. Are you on 2.3.0 now? Does WiFi work?

Just to confirm, you only pressed the FC boot button, not the ELRS boot button?