diff --git a/libraries/AP_HAL_ChibiOS/hwdef/SPRacingH7/README.md b/libraries/AP_HAL_ChibiOS/hwdef/SPRacingH7/README.md new file mode 100644 index 0000000000..f31370c7e9 --- /dev/null +++ b/libraries/AP_HAL_ChibiOS/hwdef/SPRacingH7/README.md @@ -0,0 +1,95 @@ +# Serious Pro Racing H6 Extreme Flight Controller + +The SPRacingH7 Extreme is a flight controller produced by [Seriously Pro Racing](http://www.seriouslypro.com/). + +## Features + + - MCU - STM32H750 32-bit processor running at 400 MHz + - 16MByte Serial NOR flash via QuadSPI + - IMUs - 2x ICM20602 + - Barometer - BMP388 + - OSD - AT7456E + - Onboard Flash: 128Mbits + - 7x UARTs (1,2,3,4,5,6,8) + - 11x PWM Outputs (10 Motor Output, 1 LED) + - Battery input voltage: 2S-6S + - BEC 5V 1A + +## Pinout + +![SPRacingH7 Board](SPRacingH7_Board.JPG "SPRacingH7") + +## 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. + + - SERIAL0 -> USB + - SERIAL1 -> UART1 (DMA-enabled) + - SERIAL2 -> UART2 (RCIN one wire, DMA-enabled) + - SERIAL3 -> UART3 (DMA-enabled) + - SERIAL4 -> UART4 (DMA-enabled) + - SERIAL5 -> UART5 (DMA-enabled) + - SERIAL6 -> UART6 (On motor pads 7/8, with alt config 1, DMA-enabled) + - SERIAL8 -> UART8 (DMA-enabled) + +## RC Input + +RC input is configured on the T2 (UART2_TX) pin. It supports all serial RC +protocols. For protocols requiring half-duplex serial to transmit +telemetry (such as FPort) you should setup SERIAL2 as an RC input serial port, +with half-duplex, pin-swap and inversion enabled. + +## FrSky Telemetry + +FrSky Telemetry is supported using the T2 pin (UART2 transmit). You need to set the following parameters to enable support for FrSky S.PORT + + - SERIAL2_PROTOCOL 10 + - SERIAL2_OPTIONS 7 + +## OSD Support + +The SPRacingH7 supports OSD using OSD_TYPE 1 (MAX7456 driver). + +## PWM Output + +The SPRacingH7 supports up to 11 PWM outputs. The pads for motor output +M1 to M4 on the motor connectors and M5 to M8 on separate pads, plus +M11 for LED strip or another PWM output. M9 and M10 are only available on the stacking connector. + +The PWM is in 5 groups: + + - PWM 1-4 in group1 + - PWM 5, 6 in group2 + - PWM 7, 8 in group3 + - PWM 9, 10 in group4 + - PWM 11 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 +to use DShot. Channels 1-4 support bi-directional dshot. + +## Battery Monitoring + +The board has a builting voltage and current sensor. The current +sensor can read up to 130 Amps. The voltage sensor can handle up to 6S +LiPo batteries. + +The correct battery setting parameters are: + + - BATT_MONITOR 4 + - BATT_VOLT_PIN 10 + - BATT_CURR_PIN 11 + - BATT_VOLT_MULT 11.1 + - BATT_AMP_PERVLT 59.5 + +## Compass + +The SPRacingH7 does not have a builtin compass, but you can attach an external compass using I2C on the SDA and SCL pads. + +## Loading Firmware + +Since this board stores the flight control software on external flash the initial firmware load should be done using the +SPRacing SSBL (https://github.com/spracing/ssbl). Please follow the instructions for loading PX4 firmware to load ArduPilot. +A convenience script is provided Tools/scripts/ssbl_uploader.sh to perform the required steps. +It should also be possible to load the ArduPilot bootloader via DFU, but doing so will invalidate your warranty. diff --git a/libraries/AP_HAL_ChibiOS/hwdef/SPRacingH7/SPRacingH7_Board.JPG b/libraries/AP_HAL_ChibiOS/hwdef/SPRacingH7/SPRacingH7_Board.JPG new file mode 100644 index 0000000000..bde98e1a7b Binary files /dev/null and b/libraries/AP_HAL_ChibiOS/hwdef/SPRacingH7/SPRacingH7_Board.JPG differ diff --git a/libraries/AP_HAL_ChibiOS/hwdef/SPRacingH7/defaults.parm b/libraries/AP_HAL_ChibiOS/hwdef/SPRacingH7/defaults.parm index e8a9591241..d521a5f59d 100644 --- a/libraries/AP_HAL_ChibiOS/hwdef/SPRacingH7/defaults.parm +++ b/libraries/AP_HAL_ChibiOS/hwdef/SPRacingH7/defaults.parm @@ -4,3 +4,4 @@ NTF_LED_TYPES 257 # setup SERIAL2 for RCIN SERIAL2_BAUD 115 +SERIAL2_OPTIONS 8 diff --git a/libraries/AP_HAL_ChibiOS/hwdef/SPRacingH7/hwdef.dat b/libraries/AP_HAL_ChibiOS/hwdef/SPRacingH7/hwdef.dat index 103c4090b2..237aada341 100644 --- a/libraries/AP_HAL_ChibiOS/hwdef/SPRacingH7/hwdef.dat +++ b/libraries/AP_HAL_ChibiOS/hwdef/SPRacingH7/hwdef.dat @@ -27,7 +27,7 @@ EXT_FLASH_RESERVE_END_KB 448 I2C_ORDER I2C1 # order of UARTs (and USB) -SERIAL_ORDER OTG1 USART1 USART2 USART3 UART4 UART5 EMPTY EMPTY UART8 +SERIAL_ORDER OTG1 USART1 USART2 USART3 UART4 UART5 USART6 EMPTY UART8 # Buzzer - DMA timer channel use by LEDs PD7 BUZZER OUTPUT GPIO(80) LOW @@ -86,7 +86,6 @@ PB14 USART1_TX USART1 # USART2 (RCIN) PD5 USART2_TX USART2 -PD6 USART2_RX USART2 ALT(1) define HAL_SERIAL2_PROTOCOL SerialProtocol_RCIN # USART3 @@ -101,6 +100,10 @@ PD1 UART4_TX UART4 PB5 UART5_RX UART5 PB13 UART5_TX UART5 +# UART6 +PC7 USART6_RX USART6 ALT(1) +PC6 USART6_TX USART6 ALT(1) + # UART8 PE0 UART8_RX UART8 PE1 UART8_TX UART8 @@ -136,6 +139,12 @@ PC7 TIM8_CH2 TIM8 PWM(8) GPIO(57) # M8 PD14 TIM4_CH3 TIM4 PWM(9) GPIO(58) # M9 PD15 TIM4_CH4 TIM4 PWM(10) GPIO(59) # M10 +# Motor outputs on the stacking connector +#PA6 TIM3_CH1 TIM3 PWM(1) GPIO(61) # M11 +#PA7 TIM3_CH2 TIM3 PWM(2) GPIO(62) # M12 +#PB0 TIM3_CH3 TIM3 PWM(3) GPIO(63) # M13 +#PB1 TIM3_CH4 TIM3 PWM(4) GPIO(64) # M14 + # NeoPixel LED strip PA8 TIM1_CH1 TIM1 PWM(11) GPIO(60) PE3 LED0 OUTPUT LOW GPIO(90) # Blue LED