mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-02-21 23:33:57 -04:00
hwdef: added JHEMCUGF16F405
This commit is contained in:
parent
3fbf3368fc
commit
4b082eb579
43
libraries/AP_HAL_ChibiOS/hwdef/JHEM_JHEF405/hwdef-bl.dat
Normal file
43
libraries/AP_HAL_ChibiOS/hwdef/JHEM_JHEF405/hwdef-bl.dat
Normal file
@ -0,0 +1,43 @@
|
||||
|
||||
# hw definition file for processing by chibios_hwdef.py
|
||||
# for JHEF405 hardware.
|
||||
# thanks to betaflight for pin information
|
||||
|
||||
# MCU class and specific type
|
||||
MCU STM32F4xx STM32F405xx
|
||||
|
||||
# board ID for firmware load
|
||||
APJ_BOARD_ID AP_HW_JHEMCUGF16F405
|
||||
|
||||
# crystal frequency, setup to use external oscillator
|
||||
OSCILLATOR_HZ 8000000
|
||||
|
||||
FLASH_SIZE_KB 1024
|
||||
|
||||
# bootloader starts at zero offset
|
||||
FLASH_RESERVE_START_KB 0
|
||||
|
||||
# the location where the bootloader will put the firmware
|
||||
FLASH_BOOTLOADER_LOAD_KB 48
|
||||
|
||||
# order of UARTs (and USB)
|
||||
SERIAL_ORDER OTG1
|
||||
|
||||
# PA10 IO-debug-console
|
||||
PA11 OTG_FS_DM OTG1
|
||||
PA12 OTG_FS_DP OTG1
|
||||
|
||||
PA13 JTMS-SWDIO SWD
|
||||
PA14 JTCK-SWCLK SWD
|
||||
|
||||
# default to all pins low to avoid ESD issues
|
||||
DEFAULTGPIO OUTPUT LOW PULLDOWN
|
||||
|
||||
|
||||
# Chip select pins
|
||||
PB3 FLASH1_CS CS
|
||||
PB14 OSD1_CS CS
|
||||
PB12 GYRO1_CS CS
|
||||
|
||||
PA9 LED_BOOTLOADER OUTPUT LOW
|
||||
define HAL_LED_ON 0
|
152
libraries/AP_HAL_ChibiOS/hwdef/JHEM_JHEF405/hwdef.dat
Normal file
152
libraries/AP_HAL_ChibiOS/hwdef/JHEM_JHEF405/hwdef.dat
Normal file
@ -0,0 +1,152 @@
|
||||
|
||||
# hw definition file for processing by chibios_hwdef.py
|
||||
# for JHEM_JHEF405 hardware.
|
||||
# thanks to betaflight for pin information
|
||||
|
||||
# MCU class and specific type
|
||||
MCU STM32F4xx STM32F405xx
|
||||
|
||||
# board ID for firmware load
|
||||
# https://github.com/ArduPilot/ardupilot/blob/master/Tools/AP_Bootloader/board_types.txt
|
||||
APJ_BOARD_ID AP_HW_JHEMCUGF16F405 # 1081
|
||||
|
||||
# crystal frequency, setup to use external oscillator
|
||||
OSCILLATOR_HZ 8000000
|
||||
|
||||
FLASH_SIZE_KB 1024
|
||||
|
||||
# bootloader takes first sector
|
||||
FLASH_RESERVE_START_KB 48
|
||||
|
||||
define HAL_STORAGE_SIZE 16384
|
||||
define STORAGE_FLASH_PAGE 1
|
||||
|
||||
STM32_ST_USE_TIMER 5
|
||||
|
||||
# SPI devices
|
||||
|
||||
# SPI1
|
||||
PA5 SPI1_SCK SPI1
|
||||
PA6 SPI1_MISO SPI1
|
||||
PA7 SPI1_MOSI SPI1
|
||||
|
||||
# SPI3
|
||||
PC10 SPI3_SCK SPI3
|
||||
PC11 SPI3_MISO SPI3
|
||||
PC12 SPI3_MOSI SPI3
|
||||
|
||||
# Chip select pins
|
||||
PB3 FLASH1_CS CS
|
||||
PB14 OSD1_CS CS
|
||||
PB12 GYRO1_CS CS
|
||||
|
||||
# Beeper
|
||||
PC13 BUZZER OUTPUT GPIO(80) LOW
|
||||
define HAL_BUZZER_PIN 80
|
||||
define HAL_BUZZER_ON 1
|
||||
define HAL_BUZZER_OFF 0
|
||||
|
||||
# SERIAL ports
|
||||
SERIAL_ORDER OTG1 USART1 USART2 USART3 UART4 EMPTY USART6
|
||||
# PA10 IO-debug-console
|
||||
PA11 OTG_FS_DM OTG1
|
||||
PA12 OTG_FS_DP OTG1
|
||||
|
||||
# USART1
|
||||
PA10 USART1_RX USART1
|
||||
PB6 USART1_TX USART1
|
||||
define DEFAULT_SERIAL1_PROTOCOL SerialProtocol_RCIN
|
||||
|
||||
# USART2
|
||||
PD5 USART2_TX USART2
|
||||
PD6 USART2_RX USART2
|
||||
|
||||
# USART3
|
||||
PB10 USART3_TX USART3
|
||||
PB11 USART3_RX USART3
|
||||
|
||||
# UART4
|
||||
PA0 UART4_TX UART4
|
||||
PA1 UART4_RX UART4
|
||||
define DEFAULT_SERIAL4_PROTOCOL SerialProtocol_SmartAudio
|
||||
|
||||
# USART6
|
||||
PC6 USART6_TX USART6 NODMA
|
||||
PC7 USART6_RX USART6 NODMA
|
||||
|
||||
# I2C ports
|
||||
I2C_ORDER I2C1
|
||||
# I2C1
|
||||
PB8 I2C1_SCL I2C1
|
||||
PB9 I2C1_SDA I2C1
|
||||
|
||||
# Servos
|
||||
|
||||
# ADC ports
|
||||
|
||||
# ADC1
|
||||
PC0 RSSI_ADC ADC1
|
||||
define BOARD_RSSI_ANA_PIN 10
|
||||
PC2 BATT_CURRENT_SENS ADC1 SCALE(1)
|
||||
define HAL_BATT_CURR_PIN 12
|
||||
define HAL_BATT_CURR_SCALE 58.8
|
||||
PC3 BATT_VOLTAGE_SENS ADC1 SCALE(1)
|
||||
define HAL_BATT_VOLT_PIN 13
|
||||
define HAL_BATT_VOLT_SCALE 11.0
|
||||
define HAL_BATT_MONITOR_DEFAULT 4
|
||||
|
||||
# MOTORS
|
||||
PB0 TIM3_CH3 TIM3 PWM(1) GPIO(50) # M1
|
||||
PB1 TIM3_CH4 TIM3 PWM(2) GPIO(51) # M2
|
||||
PA3 TIM2_CH4 TIM2 PWM(3) GPIO(52) # M3
|
||||
PA2 TIM2_CH3 TIM2 PWM(4) GPIO(53) # M4
|
||||
PB5 TIM3_CH2 TIM3 PWM(5) GPIO(54) # M5
|
||||
PB7 TIM4_CH2 TIM4 PWM(6) GPIO(55) # M6
|
||||
PC9 TIM8_CH4 TIM8 PWM(7) GPIO(56) # M7
|
||||
PC8 TIM8_CH3 TIM8 PWM(8) GPIO(57) # M8
|
||||
|
||||
# LEDs
|
||||
PA9 TIM1_CH2 TIM1 PWM(9) GPIO(58) # LED
|
||||
|
||||
PC14 LED0 OUTPUT LOW GPIO(90)
|
||||
define HAL_GPIO_A_LED_PIN 90
|
||||
define HAL_GPIO_LED_OFF 1
|
||||
|
||||
# Dataflash setup
|
||||
SPIDEV dataflash SPI3 DEVID1 FLASH1_CS MODE3 104*MHZ 104*MHZ
|
||||
|
||||
define HAL_LOGGING_DATAFLASH_ENABLED 1
|
||||
|
||||
# OSD setup
|
||||
SPIDEV osd SPI3 DEVID1 OSD1_CS MODE0 10*MHZ 10*MHZ
|
||||
|
||||
define OSD_ENABLED 1
|
||||
define HAL_OSD_TYPE_DEFAULT 1
|
||||
ROMFS_WILDCARD libraries/AP_OSD/fonts/font*.bin
|
||||
|
||||
# Barometer setup
|
||||
BARO BMP280 I2C:0:0x76
|
||||
|
||||
# Barometer setup
|
||||
BARO DPS310 I2C:0:0x76
|
||||
|
||||
# IMU setup
|
||||
SPIDEV icm42688 SPI1 DEVID1 GYRO1_CS MODE3 1*MHZ 8*MHZ
|
||||
IMU Invensensev3 SPI:icm42688 ROTATION_PITCH_180
|
||||
DMA_NOSHARE TIM3_UP TIM2_UP TIM4_UP TIM8_UP SPI1*
|
||||
DMA_PRIORITY TIM3_UP TIM2_UP TIM4_UP TIM8_UP SPI1*
|
||||
|
||||
# no built-in compass, but probe the i2c bus for all possible
|
||||
# external compass types
|
||||
define ALLOW_ARM_NO_COMPASS
|
||||
define HAL_PROBE_EXTERNAL_I2C_COMPASSES
|
||||
define HAL_I2C_INTERNAL_MASK 0
|
||||
define HAL_COMPASS_AUTO_ROT_DEFAULT 2
|
||||
define HAL_DEFAULT_INS_FAST_SAMPLE 3
|
||||
# Motor order implies Betaflight/X for standard ESCs
|
||||
define HAL_FRAME_TYPE_DEFAULT 12
|
||||
|
||||
include ../include/minimize_common.inc
|
||||
# define AP_GPS_NMEA_ENABLED 1
|
||||
|
||||
AUTOBUILD_TARGETS Copter
|
Binary file not shown.
After Width: | Height: | Size: 169 KiB |
Binary file not shown.
After Width: | Height: | Size: 715 KiB |
BIN
libraries/AP_HAL_ChibiOS/hwdef/JHEM_JHEF405/jhemcu-gf16-bmi.jpg
Normal file
BIN
libraries/AP_HAL_ChibiOS/hwdef/JHEM_JHEF405/jhemcu-gf16-bmi.jpg
Normal file
Binary file not shown.
After Width: | Height: | Size: 111 KiB |
111
libraries/AP_HAL_ChibiOS/hwdef/JHEM_JHEF405/readme.md
Normal file
111
libraries/AP_HAL_ChibiOS/hwdef/JHEM_JHEF405/readme.md
Normal file
@ -0,0 +1,111 @@
|
||||
# JHEMCU GF16-BMI stack F405 (JHEM_JHEF405) Flight Controller with 13A ESC
|
||||
|
||||
JHEMCU GF16-BMI stack F405 Flight control 13A ESC
|
||||
produced by [JHEMCU](https://www.jhemcu.com/)
|
||||
|
||||
There are 5 serial ports (UART1, UART2, UART3, UART4, UART6), 8 motor ports, 1 I2C port, and 1 SBUS interface (the serial port used by SBUS is RX1), with WS2812 interface reserved. Built in black box 16MB and barometer, with buzzer interface and camera interface.
|
||||
|
||||
|
||||
data:image/s3,"s3://crabby-images/11f3a/11f3ad4db501b139fd7456374dfeebee257b13f5" alt="JHEMCU GF16-BMI stack"
|
||||
|
||||
### Specs:
|
||||
**Flight control parameters:**
|
||||
* MCU: STM32F405
|
||||
* Gyroscope/Accelerometer: BMI270
|
||||
* OSD: AT7456E
|
||||
* Barometer: BMP280
|
||||
* Black box: 16MB
|
||||
* I2C: Support
|
||||
* BEC: 5V/3A
|
||||
* UART: UART1 (RC), UART2, UART3, UART4, UART6
|
||||
* USB: micro USB
|
||||
* Size: 16 * 16MM M3
|
||||
* Receiver: ELRS (CRSF), TBS (CRSF), SBUS, IBUS, DSM2, DSMX
|
||||
* Support programmable LED such as WS2812
|
||||
* Support buzzer
|
||||
* Built-in voltage and current sensors
|
||||
|
||||
**Electrical adjustment parameters:**
|
||||
|
||||
* Input voltage: 2-4S LiPo/2-4S HV LiPo
|
||||
* BEC output: None
|
||||
* Continuous working current of single electric regulator: 13A * 4
|
||||
* External electrical adjustment size: 24 * 25mm (including the maximum size of solder pads and protruding points)
|
||||
* Screw hole pitch 16 * 16MM, hole diameter 3MM
|
||||
* Firmware: BLHELI_ S G_ H_ 30_ 16_ 7. HEX
|
||||
* Supports Dshot600, Dshot300, Dshot150, Oneshot125, Multispot, PWM control signals
|
||||
|
||||
Weight: flight control+electric adjustment=5.8g
|
||||
|
||||
|
||||
## Pinout
|
||||
|
||||
data:image/s3,"s3://crabby-images/6570f/6570f4c781b7af311ac51f47b4b20e095beb157b" alt="JHEMCU GF16-BMI stack"
|
||||
data:image/s3,"s3://crabby-images/9bf81/9bf81ab3fc95cacbd8b2aeec5c0b5c8464684fb7" alt="JHEMCU GF16-BMI stack"
|
||||
|
||||
## 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) - RC Input/Output |
|
||||
|SERIAL2|TX2/RX2|USART2 (DMA RX only) - MAVLink2 |
|
||||
|SERIAL3|TX3/RX3|USART3 (DMA TX only) - GPS1 |
|
||||
|SERIAL4|TX4/RX4|UART4 (DMA TX only) - VTX |
|
||||
|SERIAL6|TX6/RX6|USART6 - User |
|
||||
|
||||
## RC Input
|
||||
|
||||
SBUS input must be on SBUS pin, all others can use RX1, CRSF/ELRS/SRXL2 must also use TX pin
|
||||
|
||||
## OSD Support
|
||||
|
||||
The GSF405A supports OSD using OSD_TYPE 1 (MAX7456 driver).
|
||||
|
||||
## PWM Output
|
||||
|
||||
The JHEM_JHEF405 supports up to 9 PWM outputs (PWM9 is the serial LED output, by default). All outputs support DShot.
|
||||
|
||||
The PWM is in 5 groups:
|
||||
|
||||
* PWM 1,2,5 in group1
|
||||
* PWM 3,4 in group2
|
||||
* PWM 6 in group3
|
||||
* PWM 7,8 in group4
|
||||
* PWM 9 in group5
|
||||
|
||||
Channels within the same group need to use the same output rate. If any channel in a group uses DShot then all channels in that group would need to use DShot.
|
||||
|
||||
## Battery Monitoring
|
||||
|
||||
The board has a built-in voltage and current sensors.
|
||||
|
||||
The correct battery setting parameters are:
|
||||
|
||||
- BATT_MONITOR 4
|
||||
- BATT_VOLT_PIN 13
|
||||
- BATT_VOLT_SCALE 11.0
|
||||
- BATT_CURR_PIN 12
|
||||
- BATT_CURR_SCALE 58.8
|
||||
|
||||
These are set by default in the firmware and shouldn't need to be adjusted
|
||||
|
||||
## Compass
|
||||
|
||||
The JHEM_JHEF405 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 PWM 9 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.
|
Loading…
Reference in New Issue
Block a user