mirror of https://github.com/ArduPilot/ardupilot
AP_HAL_ChibiOS: Added RADIX2HD
This commit is contained in:
parent
5664c0a142
commit
232fdd51da
|
@ -0,0 +1,114 @@
|
|||
# BrainFPV RADIX 2 HD Flight Controller
|
||||
|
||||
The BrainFPV RADIX 2 HD is a flight controller primarily intended for
|
||||
First Person View (FPV) applications that use a HD (digital) FPV system.
|
||||
|
||||
For the full documentation, refer to the [BrainFPV website](https://www.brainfpv.com/kb/radix-2-hd/).
|
||||
|
||||
## Features
|
||||
|
||||
- STM32H750 microcontroller
|
||||
- IMU: Bosch Sensortec BMI270
|
||||
- Barometer: Infineon DPS310
|
||||
- Onboard flash: 16 MB connected via QUADSPI
|
||||
- microSD slot
|
||||
- 5 UARTs plus USB (6 UARTs with alternate board config)
|
||||
- 10 PWM outputs (8 supporting BDSHOT on dual 4-in-1 ESC connectors)
|
||||
- I2C and CAN port
|
||||
- Builtin RGB LED
|
||||
- Analog input for voltage sensing, up to 12S (52 V)
|
||||
- Analog input for current sensing
|
||||
- Analog input for RSSI
|
||||
- External buzzer
|
||||
- USB Type-C connector
|
||||
- Battery voltage 3S-8S (35 V)
|
||||
- 5 V / 1.5 A voltage regulator for powering flight controller and external devices
|
||||
- 9 V / 2 A voltage regulator for HD FPV system (can be turned on/off using the Relay2 switch)
|
||||
- Size: 37 x 37 mm (30.5 mm hole spacing)
|
||||
- Weight: 7g
|
||||
- Made in the USA, NDAA compliant
|
||||
|
||||
## Pinout
|
||||
|
||||
![RADIX2HD Board Top](radix_2_hd_pinout_top.png "RADIX2HD Top")
|
||||
|
||||
![RADIX2HD Board Bottom](radix_2_hd_pinout_bottom.png "RADIX2HD Bottom")
|
||||
|
||||
Refer to the [full documentation](https://www.brainfpv.com/kb/radix-2-hd/) for details
|
||||
and how to use the "PWR:VBAT" jumper.
|
||||
|
||||
## UART Mapping
|
||||
|
||||
- SERIAL0 -> USB
|
||||
- SERIAL1 -> UART1 (DMA-enabled, MSP DisplayPort OSD)
|
||||
- SERIAL2 -> UART2 (DMA-enabled, GPS)
|
||||
- SERIAL3 -> UART3 (DMA-enabled, RCin)
|
||||
- SERIAL4 -> UART4 (spare)
|
||||
- SERIAL5 -> UART5 (spare)
|
||||
- SERIAL6 -> UART6 (spare, PWM 9 and 10 by default, use BRD_ALT_CONFIG = 1 for UART)
|
||||
|
||||
## RC Input
|
||||
|
||||
By default, SERIAL3 is used for RC input. The RC receiver 5 V pad next to RX3 ("+") is
|
||||
also powered from USB for easy and safe configuration without having to connect the main
|
||||
battery.
|
||||
|
||||
## PWM Output
|
||||
|
||||
The RADIX 2 HD has a total of 10 PWM outputs. The first 8 outputs support BDSHOT and
|
||||
are on two 4-in-1 ESC connectors. The PWM outputs are in groups of 2 channels each,
|
||||
all channels in the same group need to use the same configuration / rate.
|
||||
|
||||
- PWM 1-2 Group 1
|
||||
- PWM 3-4 Group 2
|
||||
- PWM 5-6 Group 3
|
||||
- PWM 7-8 Group 4
|
||||
- PWM 9-10 Group 5 (These are on the TX6 and RX6 pads that can also be used for SERIAL6)
|
||||
|
||||
## Analog inputs
|
||||
|
||||
The RADIX 2 HD has 3 analog inputs:
|
||||
|
||||
- ADC Pin 10 -> Battery Voltage (VBAT pin, builtin 1:17.6 voltage divider)
|
||||
- ADC Pin 3 -> Battery Current Sensor (CUR pin)
|
||||
- ADC Pin 11 -> RSSI voltage monitoring (RSSI pad)
|
||||
|
||||
## Battery Monitoring
|
||||
|
||||
The RADIX 2 HD can monitor battery voltages up to 12S using a built-in voltage divider.
|
||||
The board itself can be powered by battery voltages up to 8S (35 V) and there is a jumper
|
||||
to use the same pin for battery voltage monitoring and for powering the board.
|
||||
|
||||
WARNING Powering the board with more than 8S (35 V) with the "PWR:VBAT" jumper soldered
|
||||
will damage it. Refer to the official documentation for more details.
|
||||
|
||||
In addition to voltage sensing, the board also has an input for an external current sensor.
|
||||
|
||||
## Loading Firmware
|
||||
|
||||
The RADIX 2 HD uses a proprietary bootloader. To load firmware, download the firmware binary file
|
||||
from the [BrainFPV website](https://www.brainfpv.com/firmware) and copy it to the USB drive
|
||||
that appears when connecting the RADIX 2 HD to your computer when it is in bootloader mode
|
||||
(hold the BOOT button and release when connecting to USB).
|
||||
|
||||
Note: When using Ardupilot, it is necessary to have a microSD card inserted, without it
|
||||
the firmware won't run.
|
||||
|
||||
Alternatively, you can create your own firmware file using the [BrainFPV Firmware Packer](https://github.com/BrainFPV/brainfpv_fw_packer).
|
||||
To create a file for Ardupilot, install the BrainFPV Firmware Packer:
|
||||
|
||||
pip install git+https://github.com/BrainFPV/brainfpv_fw_packer.git
|
||||
|
||||
After that, build the Copter firmware:
|
||||
|
||||
./waf configure --board RADIX2HD
|
||||
./waf copter
|
||||
|
||||
Finally, use the firmware packer script to create the firmware file that can be used with the
|
||||
BrainFPV bootloader:
|
||||
|
||||
./libraries/AP_HAL_ChibiOS/hwdef/RADIX2HD/pack_firmware.sh copter
|
||||
|
||||
To use it, copy the resulting `arducopter_{VERSION}_brainfpv.bin` to the USB drive that appears
|
||||
when the RADIX 2 HD is in bootloader mode. Once it finishes copying, safely remove the drive.
|
||||
At this point the RADIX 2 HD will reboot and run the Copter firmware.
|
|
@ -0,0 +1,13 @@
|
|||
# CRSF receiver on UART3
|
||||
SERIAL3_PROTOCOL 23
|
||||
RSSI_TYPE 3
|
||||
|
||||
# MSP DisplayPort OSD on UART1
|
||||
OSD_TYPE 5
|
||||
SERIAL1_PROTOCOL 42
|
||||
|
||||
# GPS on UART2
|
||||
SERIAL2_PROTOCOL 5
|
||||
|
||||
# 9V regulator switch, ON on boot
|
||||
RELAY_DEFAULT 1
|
|
@ -0,0 +1,177 @@
|
|||
# hw definition file for processing by chibios_pins.py
|
||||
# for BrainFPV RADIX 2 HD
|
||||
|
||||
# MCU class and specific type
|
||||
MCU STM32H7xx STM32H750xx
|
||||
|
||||
# board ID for firmware load
|
||||
APJ_BOARD_ID 1118
|
||||
|
||||
# crystal frequency, setup to use external oscillator
|
||||
OSCILLATOR_HZ 16000000
|
||||
|
||||
MCU_CLOCKRATE_MHZ 480
|
||||
|
||||
env OPTIMIZE -O2
|
||||
|
||||
define HAL_WITH_EKF_DOUBLE 0
|
||||
|
||||
STM32_ST_USE_TIMER 13
|
||||
define CH_CFG_ST_RESOLUTION 16
|
||||
|
||||
# internal flash is off limits
|
||||
FLASH_SIZE_KB 128
|
||||
FLASH_RESERVE_START_KB 0
|
||||
define HAL_FLASH_PROTECTION 1
|
||||
|
||||
EXT_FLASH_SIZE_MB 16
|
||||
EXT_FLASH_RESERVE_START_KB 4096
|
||||
EXT_FLASH_RESERVE_END_KB 0
|
||||
|
||||
# Supports upto 2 MBits/s
|
||||
CANFD_SUPPORTED 2
|
||||
|
||||
# only one I2C bus
|
||||
I2C_ORDER I2C1
|
||||
|
||||
# order of UARTs (and USB)
|
||||
SERIAL_ORDER OTG1 USART1 USART2 USART3 UART4 UART5 USART6
|
||||
|
||||
# I2C1 for baro
|
||||
PB6 I2C1_SCL I2C1 PULLUP
|
||||
PB7 I2C1_SDA I2C1 PULLUP
|
||||
|
||||
# Analog inputs
|
||||
PC0 BATT_VOLTAGE_SENS ADC1 SCALE(1)
|
||||
PA6 BATT_CURRENT_SENS ADC1 SCALE(1)
|
||||
PC1 RSSI_ADC ADC1
|
||||
|
||||
define HAL_BATT_MONITOR_DEFAULT 4
|
||||
define HAL_BATT_VOLT_PIN 10
|
||||
define HAL_BATT_CURR_PIN 3
|
||||
define HAL_BATT_VOLT_SCALE 17.6
|
||||
define HAL_BATT_CURR_SCALE 28.5
|
||||
define BOARD_RSSI_ANA_PIN 11
|
||||
|
||||
# Debug
|
||||
PA13 JTMS-SWDIO SWD
|
||||
PA14 JTCK-SWCLK SWD
|
||||
|
||||
# USB
|
||||
PA11 OTG_FS_DM OTG1
|
||||
PA12 OTG_FS_DP OTG1
|
||||
|
||||
# USART1 (HD OSD)
|
||||
PB15 USART1_RX USART1
|
||||
PB14 USART1_TX USART1
|
||||
|
||||
# USART2 (GPS)
|
||||
PD6 USART2_RX USART2
|
||||
PD5 USART2_TX USART2
|
||||
|
||||
# USART3 (RC input)
|
||||
PB11 USART3_RX USART3
|
||||
PD8 USART3_TX USART3
|
||||
|
||||
# UART4 (ESC telemetry)
|
||||
PB8 UART4_RX UART4 NODMA
|
||||
PA0 UART4_TX UART4 NODMA
|
||||
|
||||
# UART5 (spare)
|
||||
PB12 UART5_RX UART5 NODMA
|
||||
PB13 UART5_TX UART5 NODMA
|
||||
|
||||
# USART6 (spare)
|
||||
PC7 USART6_RX USART6 NODMA ALT(1)
|
||||
PC6 USART6_TX USART6 NODMA ALT(1)
|
||||
|
||||
# TODO: USART7 (RX only)
|
||||
|
||||
# CAN bus
|
||||
PD0 CAN1_RX CAN1
|
||||
PD1 CAN1_TX CAN1
|
||||
|
||||
# SP1 for BMI270
|
||||
PA5 SPI1_SCK SPI1
|
||||
PB4 SPI1_MISO SPI1
|
||||
PD7 SPI1_MOSI SPI1
|
||||
PD3 BMI270_CS CS
|
||||
|
||||
# SD card
|
||||
PC8 SDMMC1_D0 SDMMC1
|
||||
PC9 SDMMC1_D1 SDMMC1
|
||||
PC10 SDMMC1_D2 SDMMC1
|
||||
PC11 SDMMC1_D3 SDMMC1
|
||||
PC12 SDMMC1_CK SDMMC1
|
||||
PD2 SDMMC1_CMD SDMMC1
|
||||
|
||||
# QuadSPI Flash running at 120 MHz from HCLK
|
||||
define HAL_FORCE_CLOCK_INIT
|
||||
define STM32_QSPISEL STM32_QSPISEL_HCLK
|
||||
PD11 QUADSPI_BK1_IO0 QUADSPI1 SPEED_HIGH
|
||||
PD12 QUADSPI_BK1_IO1 QUADSPI1 SPEED_HIGH
|
||||
PE2 QUADSPI_BK1_IO2 QUADSPI1 SPEED_HIGH
|
||||
PA1 QUADSPI_BK1_IO3 QUADSPI1 SPEED_HIGH
|
||||
PB10 QUADSPI_BK1_NCS QUADSPI1 SPEED_HIGH
|
||||
PB2 QUADSPI_CLK QUADSPI1 SPEED_HIGH
|
||||
|
||||
# Motors
|
||||
PE11 TIM1_CH2 TIM1 PWM(1) GPIO(50) BIDIR # M1
|
||||
PE13 TIM1_CH3 TIM1 PWM(2) GPIO(51) BIDIR # M2
|
||||
PA15 TIM2_CH1 TIM2 PWM(3) GPIO(52) BIDIR # M3
|
||||
PA2 TIM2_CH3 TIM2 PWM(4) GPIO(53) BIDIR # M4
|
||||
PB5 TIM3_CH2 TIM3 PWM(5) GPIO(54) BIDIR # M5
|
||||
PB0 TIM3_CH3 TIM3 PWM(6) GPIO(55) BIDIR # M6
|
||||
PD13 TIM4_CH2 TIM4 PWM(7) GPIO(56) BIDIR # M7
|
||||
PD14 TIM4_CH3 TIM4 PWM(8) GPIO(57) BIDIR # M8
|
||||
|
||||
# PWM output on UART6 TX and RX pins
|
||||
PC6 TIM8_CH1 TIM8 PWM(9) GPIO(58) NODMA # TX6
|
||||
PC7 TIM8_CH2 TIM8 PWM(10) GPIO(59) NODMA # RX6
|
||||
|
||||
# RGB LED output: Currently not working: Needs to be inverted due to level shifter
|
||||
PA3 TIM5_CH4 TIM5 PWM(11) GPIO(60)
|
||||
|
||||
# Buzzer pin
|
||||
PE4 BUZZER OUTPUT LOW PULLDOWN GPIO(80)
|
||||
define HAL_BUZZER_PIN 80
|
||||
define AP_NOTIFY_TONEALARM_ENABLED 1
|
||||
|
||||
# LEDs
|
||||
PE5 LED_RED OUTPUT HIGH OPENDRAIN GPIO(10)
|
||||
PE6 LED_GREEN OUTPUT HIGH OPENDRAIN GPIO(11)
|
||||
PA7 LED_BLUE OUTPUT HIGH OPENDRAIN GPIO(12)
|
||||
|
||||
define HAL_GPIO_A_LED_PIN 10
|
||||
define HAL_GPIO_B_LED_PIN 11
|
||||
define HAL_GPIO_C_LED_PIN 12
|
||||
|
||||
define HAL_GPIO_LED_ON 0
|
||||
define HAL_GPIO_LED_OFF 1
|
||||
|
||||
define HAL_HAVE_PIXRACER_LED
|
||||
|
||||
# 9V regulator switch
|
||||
PC14 VTX_PWR OUTPUT HIGH GPIO(81)
|
||||
define RELAY2_PIN_DEFAULT 81
|
||||
|
||||
SPIDEV bmi270 SPI1 DEVID1 BMI270_CS MODE3 2*MHZ 10*MHZ
|
||||
|
||||
IMU BMI270 SPI:bmi270 ROTATION_ROLL_180
|
||||
|
||||
BARO DPS310 I2C:0:0x76
|
||||
|
||||
# filesystem setup on sdcard
|
||||
define HAL_OS_FATFS_IO 1
|
||||
define HAL_BOARD_LOG_DIRECTORY "/APM/LOGS"
|
||||
define HAL_BOARD_TERRAIN_DIRECTORY "/APM/TERRAIN"
|
||||
|
||||
define STM32_PWM_USE_ADVANCED TRUE
|
||||
|
||||
define HAL_STORAGE_SIZE 16384
|
||||
|
||||
# DMA
|
||||
DMA_PRIORITY SPI1*
|
||||
DMA_NOSHARE SPI1* TIM1* TIM2* TIM3* TIM4*
|
||||
NODMA I2C*
|
||||
define STM32_I2C_USE_DMA FALSE
|
|
@ -0,0 +1,24 @@
|
|||
#!/usr/bin/env bash
|
||||
|
||||
# Example script to pack firmware for RADIX 2 HD
|
||||
# Get the firmware packer tool from here: https://github.com/BrainFPV/brainfpv_fw_packer
|
||||
|
||||
# Get version information
|
||||
GIT_VER=$(git describe HEAD 2>&1)
|
||||
GIT_SHA1=$(git rev-parse HEAD)
|
||||
|
||||
TARGET_BUILD_DIR=./build/RADIX2HD/bin
|
||||
FW_ELF=${TARGET_BUILD_DIR}/ardu$1
|
||||
FW_HEX=${TARGET_BUILD_DIR}/ardu$1.hex
|
||||
FW_PACKED=${TARGET_BUILD_DIR}/ardu$1_${GIT_VER}_brainfpv.bin
|
||||
|
||||
# Create hex file
|
||||
arm-none-eabi-objcopy -O ihex ${FW_ELF} ${FW_HEX}
|
||||
|
||||
# Create binary for BrainFPV bootloader
|
||||
brainfpv_fw_packer.py \
|
||||
--name ardu$1 \
|
||||
--version ${GIT_VER} \
|
||||
--sha1 ${GIT_SHA1} \
|
||||
--in ${FW_HEX} --out ${FW_PACKED} \
|
||||
--dev radix2hd -t firmware -b 0x90400000 -z --noheader
|
Binary file not shown.
After Width: | Height: | Size: 104 KiB |
Binary file not shown.
After Width: | Height: | Size: 130 KiB |
Loading…
Reference in New Issue