diff --git a/libraries/AP_HAL_ChibiOS/hwdef/BETAFPV-F405-I2C/README.md b/libraries/AP_HAL_ChibiOS/hwdef/BETAFPV-F405-I2C/README.md new file mode 100644 index 0000000000..09d0013111 --- /dev/null +++ b/libraries/AP_HAL_ChibiOS/hwdef/BETAFPV-F405-I2C/README.md @@ -0,0 +1,91 @@ +# BETAFPV F405 AIO Flight Controller + +The BETAFPV F405 AIO is a flight controller produced by [BETAFPV](https://betafpv.com/collections/brushless-flight-controller/products/f4-1s-12a-aio-brushless-flight-controller-v3-0). + +## Features + + - MCU: STM32F405RGT6, 168MHz + - Gyro: ICM42688-P + - 16Mb Onboard Flash + - BEC output: 5V, 2A@4V + - Barometer: BMP280 + - OSD: AT7456E + - 5 UARTS: (UART1, UART4, UART5, UART6) + - 5 PWM outputs (4 motor outputs used internally for integrated 4-in-1 ESC and 1 integrated LED) + - Integrated 4-in-1 BlueJay ESC + +## Pinout + +![BETAFPV F405 AIO Board](../BETAFPV-F405/betafpv_f405_pinout.jpg "BETAFPV F405 AIO") + +## 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|UART1 (RX, DMA-enabled)| +|SERIAL4|TX4/RX4|UART4 (MSP DisplayPort)| +|SERIAL5|RX5|UART5 (SBUS, RX-only)| +|SERIAL6|TX6/RX6|UART6 (GPS, DMA-enabled)| + +## RC Input + +RC input is configured on the on-board ELRS on UART3 or through (UART6_RX/UART6_TX) pins. It supports all serial RC protocols. + +## OSD Support + +The BETAFPV F405 AIO supports OSD using OSD_TYPE 1 (MAX7456 driver). + +## PWM Output + +The BETAFPV F405 AIO has 4 PWM outputs internally connected to its 4-in-1 ESC. The pads for motor output are M1 to M4 on the board. All 4 outputs support bi-directional DShot and DShot, as well as all PWM types. The default configuration is for bi-directional DShot using the already installed BlueJay firmware. + +The PWM are in in two groups: + + - PWM 1-2 in group1 + - PWM 3-4 in group2 + - PWM 5 in group3 + +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 +to use DShot. + +## Battery Monitoring + +The board has a builtin voltage sensor and a current sensor input tied to its 4 in 1 ESC current sensor. The voltage sensor can handle up to 6S +LiPo batteries. + +The correct battery setting parameters are: + + - BATT_MONITOR 4 + - BATT_VOLT_PIN 12 + - BATT_VOLT_MULT 10.9 + - BATT_CURR_PIN 13 + - BATT_CURR_MULT 50 + +These are set by default in the firmware and shouldn't need to be adjusted + +## Compass + +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 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. diff --git a/libraries/AP_HAL_ChibiOS/hwdef/BETAFPV-F405-I2C/defaults.parm b/libraries/AP_HAL_ChibiOS/hwdef/BETAFPV-F405-I2C/defaults.parm new file mode 100644 index 0000000000..9b28029b7f --- /dev/null +++ b/libraries/AP_HAL_ChibiOS/hwdef/BETAFPV-F405-I2C/defaults.parm @@ -0,0 +1,12 @@ +# setup for LEDs on chan5 +SERVO5_FUNCTION 120 +NTF_LED_TYPES 257 +NTF_LED_LEN 2 +# Bluejay installed by default +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 \ No newline at end of file diff --git a/libraries/AP_HAL_ChibiOS/hwdef/BETAFPV-F405-I2C/hwdef-bl.dat b/libraries/AP_HAL_ChibiOS/hwdef/BETAFPV-F405-I2C/hwdef-bl.dat new file mode 100644 index 0000000000..965799cb6a --- /dev/null +++ b/libraries/AP_HAL_ChibiOS/hwdef/BETAFPV-F405-I2C/hwdef-bl.dat @@ -0,0 +1 @@ +include ../BETAFPV-F405/hwdef-bl.dat diff --git a/libraries/AP_HAL_ChibiOS/hwdef/BETAFPV-F405-I2C/hwdef.dat b/libraries/AP_HAL_ChibiOS/hwdef/BETAFPV-F405-I2C/hwdef.dat new file mode 100644 index 0000000000..260d4d5a50 --- /dev/null +++ b/libraries/AP_HAL_ChibiOS/hwdef/BETAFPV-F405-I2C/hwdef.dat @@ -0,0 +1,24 @@ +# i2c version of BETAFPV-F405 + +include ../BETAFPV-F405/hwdef.dat + +# undefine the pins we are going to change +undef PB4 PB10 PB11 PC6 PA3 PA2 + +SERIAL_ORDER OTG1 USART1 EMPTY EMPTY UART4 EMPTY USART6 + +undef DEFAULT_SERIAL1_PROTOCOL +define DEFAULT_SERIAL1_PROTOCOL SerialProtocol_RCIN +define DEFAULT_SERIAL6_PROTOCOL SerialProtocol_GPS + +I2C_ORDER I2C2 +PB10 I2C2_SCL I2C2 +PB11 I2C2_SDA I2C2 +PB4 EXTERN_GPIO1 OUTPUT GPIO(82) +undef RELAY2_PIN_DEFAULT +define RELAY2_PIN_DEFAULT 82 + +PA3 TIM2_CH4 TIM2 PWM(3) GPIO(52) # M3 +PA2 TIM2_CH3 TIM2 PWM(4) GPIO(53) BIDIR # M4 + +DMA_NOSHARE SPI1* TIM2_UP TIM3_UP