hwdef: add support for JHEMCU GSF405A

This commit is contained in:
ot0tot 2022-01-16 19:52:15 -05:00 committed by Andrew Tridgell
parent b917a71431
commit 1a08a1e1a1
9 changed files with 438 additions and 0 deletions

View File

@ -156,6 +156,7 @@ AP_HW_MatekF405_TE 1054
AP_HW_SierraF412 1055
AP_HW_BEASTF7v2 1057
AP_HW_KakuteH7Mini 1058
AP_HW_JHEMCUGSF405A 1059
AP_HW_CUBEORANGE_PERIPH 1400
AP_HW_CUBEBLACK_PERIPH 1401

View File

@ -0,0 +1,3 @@
# JHEMCU GSF405A target for external receiver
include ../JHEMCU-GSF405A/hwdef-bl.dat

View File

@ -0,0 +1,28 @@
# 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 hwdef from jeanphilippehell
# thanks to betaflight for pin information (https://github.com/betaflight/unified-targets/blob/master/configs/default/JHEF-JHEF405PRO.config)
# Version of JHEMCU GSF405A target to use external RX on USART2
include ../JHEMCU-GSF405A/hwdef.data
undef PD5 PD6 PB10 PB11 PA3 PA2
undef HAL_SERIAL1_PROTOCOL
# USART2 - SBUS pad
PD5 USART2_TX USART2
PD6 USART2_RX USART2
# default Serial2 to RCIN
define HAL_SERIAL2_PROTOCOL 23
# USART3
PB10 USART3_TX USART3 NODMA
PB11 USART3_RX USART3 NODMA
# Motor outputs on AIO ESC
PA3 TIM2_CH4 TIM2 PWM(3) GPIO(52)
PA2 TIM2_CH3 TIM2 PWM(4) GPIO(53) BIDIR
DMA_PRIORITY SPI1* SPI3* TIM1_CH2 TIM2_UP TIM3_UP
DMA_NOSHARE USART2*

View File

@ -0,0 +1,95 @@
# JHEMCU GSF405A AIO Flight Controller
The JHEMCU GSF405A is a 1-2S Whoop-style (25.5mm x 25.5mm) flight controller featuring the STM32F405OG6 MCU, 4in1 5A ESCs, BMP280 barometer, 8MB flash, and an on-board ExpressLRS 2.4GHz receiver. The board weighs 3.3g, making it suitable for small or lightweight ArduPilot builds.
![JHEMCU GSF405A](../JHEMCU-GSF405A/gsf405a.jpg "JHEMCU GSF405A Top")
https://pyrodrone.com/collections/new-products/products/jhemcu-gsf405a-1s-2s-aio-f4-flight-control-w-5a-esc-elrs-2-4g-rx-25-5-25-5mm
https://www.racedayquads.com/collections/new-products/products/jhemcu-gsf405a-1-2s-toothpick-whoop-aio-flight-controller-w-8bit-5a-esc-and-elrs-2-4ghz-rx
### 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
* *Note* Bidirectional DShot requires [flashing](https://esc-configurator.com/) a compatible ESC firmware (eg [Bluejay](https://github.com/mathiasvr/bluejay))).
## Pinout
![GSF405A AIO Board](../JHEMCU-GSF405A/gsf405a_pinout.jpg "JHEMCU GSF405A Pinout")
## UART Mapping
The UARTs are marked Rn and Tn in the above pinouts. The Rn pin is the
receive pin for UARTn. The Tn pin is the transmit pin for UARTn.
|Name|Pin|Function|
|:-|:-|:-|
|SERIAL0|COMPUTER|USB|
|SERIAL1|RX1/TX1|USART1 (DMA) - Used by the on-board ELRS receiver|
|SERIAL2|TX2/RX2|USART2 (DMA - RX2/TX2/SBUS pads|
|SERIAL3|TX3/RX3|USART3|
|SERIAL4|TX4/RX4|UART4|
|SERIAL6|TX6/RX6|USART6 (DMA) - Telemetry|
## RC Input
RC input is configured on SERIAL2 (USART2), which is available on the RX2, TX2, and SBUS pads. PPM receivers are *not* supported as this input does not have a timer resource available.
*Note* A different target is available should you want to use the built-in ExpressLRS 2.4GHz receiver on USART1.
## OSD Support
The GSF405A supports OSD using OSD_TYPE 1 (MAX7456 driver).
## Motor Output
The built-in ESC is mapped to motor outputs 1-4. Bidirectional DShot is supported (requires flashing the ESC to a BLHeli_S version that supports bdshot, such as [Bluejay](esc-configurator.com)).
## Battery Monitoring
The board has a built-in voltage and current sensors.
The correct battery setting parameters are:
- BATT_MONITOR 4
- BATT_VOLT_PIN 11
- BATT_VOLT_SCALE 11
- BATT_CURR_PIN 13
- BATT_CURR_SCALE 17
These are set by default in the firmware and shouldn't need to be adjusted
## Compass
The GSF405A does not have a builtin compass, but you can attach an external compass to the I2C pins.
## LED
The board includes a LED_STRIP output, which is assigned a timer and DMA. This is the fifth PWM output.
## Loading Firmware
Initial firmware load can be done with DFU by plugging in USB with the
bootloader button pressed. Then you should load the "with_bl.hex"
firmware, using your favourite DFU loading tool.
Once the initial firmware is loaded you can update the firmware using
any ArduPilot ground station software. Updates should be done with the
*.apj firmware files.

Binary file not shown.

After

Width:  |  Height:  |  Size: 61 KiB

Binary file not shown.

After

Width:  |  Height:  |  Size: 70 KiB

View File

@ -0,0 +1,44 @@
# 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 1059
# 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

View File

@ -0,0 +1,172 @@
# 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 hwdef from jeanphilippehell
# thanks to betaflight for pin information (https://github.com/betaflight/unified-targets/blob/master/configs/default/JHEF-JHEF405PRO.config)
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
# 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)
# 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 TIM1_CH2 TIM1 PWM(5) GPIO(54)
DMA_PRIORITY SPI1* SPI3* USART3* USART6* TIM1_CH2
DMA_NOSHARE USART1_RX TIM5_CH4 TIM5_UP
# 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
# 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

View File

@ -0,0 +1,95 @@
# JHEMCU GSF405A AIO Flight Controller
The JHEMCU GSF405A is a 1-2S Whoop-style (25.5mm x 25.5mm) flight controller featuring the STM32F405OG6 MCU, 4in1 5A ESCs, BMP280 barometer, 8MB flash, and an on-board ExpressLRS 2.4GHz receiver. The board weighs 3.3g, making it suitable for small or lightweight ArduPilot builds.
![JHEMCU GSF405A](gsf405a.jpg "JHEMCU GSF405A Top")
https://pyrodrone.com/collections/new-products/products/jhemcu-gsf405a-1s-2s-aio-f4-flight-control-w-5a-esc-elrs-2-4g-rx-25-5-25-5mm
https://www.racedayquads.com/collections/new-products/products/jhemcu-gsf405a-1-2s-toothpick-whoop-aio-flight-controller-w-8bit-5a-esc-and-elrs-2-4ghz-rx
### 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
* *Note* Bidirectional DShot requires [flashing](https://esc-configurator.com/) a compatible ESC firmware (eg [Bluejay](https://github.com/mathiasvr/bluejay))).
## Pinout
![GSF405A AIO Board](gsf405a_pinout.jpg "JHEMCU GSF405A Pinout")
## UART Mapping
The UARTs are marked Rn and Tn in the above pinouts. The Rn pin is the
receive pin for UARTn. The Tn pin is the transmit pin for UARTn.
|Name|Pin|Function|
|:-|:-|:-|
|SERIAL0|COMPUTER|USB|
|SERIAL1|RX1/TX1|USART1 (DMA) - Used by the on-board ELRS receiver, but TX1/RX1 pads are also available |
|SERIAL2|TX2/RX2|USART2 |
|SERIAL3|TX3/RX3|USART3 (DMA) - GPS, located near I2C pads|
|SERIAL4|TX4/RX4|UART4|
|SERIAL6|TX6/RX6|USART6 (DMA) - Telemetry|
## RC Input
RC input is configured on SERIAL1 (USART1) connected to the ELRS receiver, configured for CRSF with `SERIAL1_PROTOCOL 23`.
*Note* A different target is available to should you want to run an external receiver on USART2 (RX2/TX2/SBUS). Note that PPM receivers are not supported as there is no timer resource available for this input.
## OSD Support
The GSF405A supports OSD using OSD_TYPE 1 (MAX7456 driver).
## Motor Output
The built-in ESC is mapped to motor outputs 1-4. Bidirectional DShot is supported (requires flashing the ESC to a BLHeli_S version that supports bdshot, such as Bluejay [esc-configurator.com]).
## Battery Monitoring
The board has a built-in voltage and current sensors.
The correct battery setting parameters are:
- BATT_MONITOR 4
- BATT_VOLT_PIN 11
- BATT_VOLT_SCALE 11
- BATT_CURR_PIN 13
- BATT_CURR_SCALE 17
These are set by default in the firmware and shouldn't need to be adjusted
## Compass
The GSF405A does not have a builtin compass, but you can attach an external compass to the I2C pins.
## LED
The board includes a LED_STRIP output, which is assigned a timer and DMA. This is the fifth PWM output.
## Loading Firmware
Initial firmware load can be done with DFU by plugging in USB with the
bootloader button pressed. Then you should load the "with_bl.hex"
firmware, using your favourite DFU loading tool.
Once the initial firmware is loaded you can update the firmware using
any ArduPilot ground station software. Updates should be done with the
*.apj firmware files.