Skip to content

Commit

Permalink
AP_HAL_ChibiOS: BARO update for BETAFPV F405
Browse files Browse the repository at this point in the history
add UART6 and VBUS to BETAFPV F405
add alt config to BETAFPV-F405 to support RELAY2 instead of UART6_TX as per betaflight
enable SBUS input on BETAFPV-F405 on UART5_RX
enable IMU temperature calibration for BETAFPV-F405
  • Loading branch information
andyp1per committed Dec 30, 2024
1 parent f62f1cd commit 06587ec
Show file tree
Hide file tree
Showing 3 changed files with 33 additions and 16 deletions.
17 changes: 10 additions & 7 deletions libraries/AP_HAL_ChibiOS/hwdef/BETAFPV-F405/README.md
Original file line number Diff line number Diff line change
Expand Up @@ -26,10 +26,10 @@ receive pin for UARTn. The Tn pin is the transmit pin for UARTn.
|:-|:-|:-|
|SERIAL0|COMPUTER|USB|
|SERIAL1|RX1/TX1|UART1 (GPS, DMA-enabled)|
|SERIAL3|TX3/RX3|UART3 (ELRS, internal)
|SERIAL4|TX4/RX4|UART4 (DJI)|
|SERIAL5|RX5|UART5 (RX-only)|
|SERIAL6|RX6|UART6 (SBUS, RX-only, inverted, DMA-enabled)|
|SERIAL3|TX3/RX3|UART3 (ELRS, internal - can be freed up through board modifications)
|SERIAL4|TX4/RX4|UART4 (MSP DisplayPort)|
|SERIAL5|RX5|UART5 (SBUS, RX-only)|
|SERIAL6|TX6/RX6|UART6 (Spare, DMA-enabled)|

## RC Input

Expand All @@ -48,8 +48,6 @@ The PWM are in in two groups:
- PWM 1-2 in group1
- PWM 3-4 in group2
- PWM 5 in group3
- PWM 6 in group4
- PWM 7 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 the group need
Expand All @@ -74,9 +72,14 @@ These are set by default in the firmware and shouldn't need to be adjusted

The BETAFPV F405 AIO does not have a builtin compass.

## GPIO Pin / Relay

The board has an IO pin on RELAY2 (GPIO pin 81) which can be enabled by setting BRD_ALT_CONFIG to 1.
This then turns UART6_TX into a relay which can be used for controlling an external LED (e.g. on the Pavo 20 Pro)

## NeoPixel LED

The board includes a NeoPixel LED on the underside which is pre-configured to output ArduPilot sequences. This is the seventh PWM output.
The board includes a NeoPixel LED on the underside which is pre-configured to output ArduPilot sequences. This is the fifth PWM output.

## Loading Firmware

Expand Down
3 changes: 3 additions & 0 deletions libraries/AP_HAL_ChibiOS/hwdef/BETAFPV-F405/defaults.parm
Original file line number Diff line number Diff line change
Expand Up @@ -7,3 +7,6 @@ SERVO_BLH_AUTO 1
SERVO_BLH_BDMASK 15
SERVO_DSHOT_ESC 2
MOT_PWM_TYPE 6

# io on alternate config is on
RELAY2_DEFAULT 1
29 changes: 20 additions & 9 deletions libraries/AP_HAL_ChibiOS/hwdef/BETAFPV-F405/hwdef.dat
Original file line number Diff line number Diff line change
Expand Up @@ -53,27 +53,33 @@ SERIAL_ORDER OTG1 USART1 EMPTY USART3 UART4 EMPTY USART6
# PA10 IO-debug-console
PA11 OTG_FS_DM OTG1
PA12 OTG_FS_DP OTG1
PC5 VBUS INPUT OPENDRAIN

# USART1 (GPS)
PA10 USART1_RX USART1
PA9 USART1_TX USART1
define DEFAULT_SERIAL1_PROTOCOL SerialProtocol_GPS

define DEFAULT_SERIAL2_PROTOCOL SerialProtocol_None
define DEFAULT_SERIAL5_PROTOCOL SerialProtocol_None

# USART3 (ELRS)
PB10 USART3_TX USART3
PB11 USART3_RX USART3
define DEFAULT_SERIAL3_PROTOCOL SerialProtocol_RCIN

# UART4 (DJI)
# UART4 (MSP)
PA0 UART4_TX UART4 NODMA
PA1 UART4_RX UART4 NODMA
define DEFAULT_SERIAL4_PROTOCOL SerialProtocol_DJI_FPV
define DEFAULT_SERIAL4_PROTOCOL SerialProtocol_MSP_DisplayPort

# UART5 (SBUS, RX-only)
PD2 UART5_RX UART5 NODMA

# USART6 (SBUS, inverted)
# USART6 (Spare)
PC7 USART6_RX USART6
PC6 USART6_TX USART6

# IO pin on alternate config
PC6 EXTERN_GPIO1 OUTPUT GPIO(81) ALT(1)
define RELAY2_PIN_DEFAULT 81

# I2C ports
I2C_ORDER
Expand Down Expand Up @@ -118,11 +124,14 @@ define HAL_OSD_TYPE_DEFAULT 1
ROMFS_WILDCARD libraries/AP_OSD/fonts/font*.bin

# BARO setup
SPIDEV baro SPI3 DEVID2 BARO1_CS MODE3 1*MHZ 8*MHZ
BARO BMP280 SPI:baro
define HAL_BARO_ALLOW_INIT_NO_BARO 1
SPIDEV baro1 SPI3 DEVID2 BARO1_CS MODE3 1*MHZ 8*MHZ
SPIDEV baro2 SPI3 DEVID2 BARO1_CS MODE3 1*MHZ 8*MHZ
BARO BMP280 SPI:baro1
BARO DPS280 SPI:baro2

define AP_BARO_BACKEND_DEFAULT_ENABLED 0
define AP_BARO_BMP280_ENABLED 1
define AP_BARO_DPS280_ENABLED 1

# IMU setup
SPIDEV imu1 SPI1 DEVID1 GYRO1_CS MODE3 1*MHZ 8*MHZ
Expand All @@ -139,6 +148,8 @@ define HAL_COMPASS_AUTO_ROT_DEFAULT 2
define HAL_DEFAULT_INS_FAST_SAMPLE 1
# Motor order implies Betaflight/X for standard ESCs
define HAL_FRAME_TYPE_DEFAULT 12
# Generally no compass so need accurate IMU source
define HAL_INS_TEMPERATURE_CAL_ENABLE 1


include ../include/minimize_fpv_osd.inc
Expand Down

0 comments on commit 06587ec

Please sign in to comment.