mirror of https://github.com/ArduPilot/ardupilot
AP_HAL_ChibiOS: hwdef for bdshot variant of SkystarsH7HD
Correct bootloader storage location for SkystarsH7HD
This commit is contained in:
parent
2c9e2abcf4
commit
291e2d0900
|
@ -0,0 +1,87 @@
|
|||
# Skystars H7 Flight Controller
|
||||
|
||||
The Skystars H7 is a flight controller produced by [Skystars](http://www.skystars-rc.com/).
|
||||
|
||||
## Features
|
||||
|
||||
- STM32H743 microcontroller
|
||||
- BMI270 IMU x2
|
||||
- BMP280 barometer
|
||||
- AT7456E OSD
|
||||
- 8 UARTs
|
||||
- 9 PWM outputs
|
||||
|
||||
## Pinout
|
||||
|
||||
![Skystars H7HD Board](SkystarsH7HD.jpg.jpg "Skystars H7HD")
|
||||
|
||||
## UART Mapping
|
||||
|
||||
The UARTs are marked RX and TX in the above pinouts. The RX pin is the
|
||||
receive pin for UARTn. The TX pin is the transmit pin for UARTn.
|
||||
|
||||
- SERIAL0 -> USB
|
||||
- SERIAL1 -> UART1 (RX, DMA-enabled)
|
||||
- SERIAL2 -> UART2 (DMA-enabled)
|
||||
- SERIAL3 -> UART3 (ESC Telem)
|
||||
- SERIAL4 -> UART4 (GPS, DMA-enabled)
|
||||
- SERIAL5 -> UART5 (VTX)
|
||||
- SERIAL6 -> UART6 (DJI FPV, DMA-enabled)
|
||||
- SERIAL7 -> UART7 (DMA-enabled)
|
||||
- SERIAL8 -> UART8
|
||||
|
||||
## RC Input
|
||||
|
||||
RC input is configured on the R6 (UART6_RX) pin. It supports all serial RC
|
||||
protocols. For protocols requiring half-duplex serial to transmit
|
||||
telemetry (such as FPort) you should setup
|
||||
SERIAL6 as an RC input serial port, with half-duplex, pin-swap
|
||||
and inversion enabled.
|
||||
|
||||
## OSD Support
|
||||
|
||||
The Skystars H7 supports OSD using OSD_TYPE 1 (MAX7456 driver).
|
||||
|
||||
## PWM Output
|
||||
|
||||
The Skystars H7 supports up to 9 PWM outputs. The pads for motor output
|
||||
M1 to M8 on the two motor connectors, plus M9 for LED strip or another
|
||||
PWM output.
|
||||
|
||||
The PWM is in 5 groups:
|
||||
|
||||
- PWM 1, 2 in group1
|
||||
- PWM 3, 4 in group2
|
||||
- PWM 5-8 in group3
|
||||
- PWM 9 in group4
|
||||
|
||||
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. Outputs 1-8 support bi-directional dshot.
|
||||
|
||||
## Battery Monitoring
|
||||
|
||||
The board has a builtin 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 10.1
|
||||
- BATT_AMP_PERVLT 17.0
|
||||
|
||||
## Compass
|
||||
|
||||
The Skystars H7 does not have a builtin compass, but you can attach an external compass using I2C on the SDA and SCL pads.
|
||||
## 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.
|
Binary file not shown.
After Width: | Height: | Size: 744 KiB |
|
@ -0,0 +1,8 @@
|
|||
# setup for Neopixel
|
||||
SERVO9_FUNCTION 120
|
||||
NTF_LED_TYPES 257
|
||||
NTF_LED_LEN 1
|
||||
# Default VTX power to on
|
||||
RELAY_DEFAULT 1
|
||||
SERIAL3_PROTOCOL 16
|
||||
RSSI_TYPE 3
|
|
@ -0,0 +1,4 @@
|
|||
# hw definition file for processing by chibios_pins.py
|
||||
# for SkystarsH7HD bootloader
|
||||
|
||||
include ../SkystarsH7HD/hwdef-bl.dat
|
|
@ -0,0 +1,44 @@
|
|||
# hw definition file for processing by chibios_pins.py
|
||||
# for SkystarsH7HD
|
||||
|
||||
include ../SkystarsH7HD/hwdef.dat
|
||||
|
||||
undef PB0 PB1 PD12 PA0 PA2 PC7 PC6 PD8 PD9 PB5 PB6 PE0 PE1
|
||||
undef HAL_I2C_INTERNAL_MASK DMA_PRIORITY DMA_NOSHARE
|
||||
|
||||
MCU_CLOCKRATE_MHZ 480
|
||||
|
||||
DMA_PRIORITY TIM3* TIM4* TIM2* SPI1* SPI3* SPI4* TIM1*
|
||||
DMA_NOSHARE TIM3* TIM4* TIM2* SPI1* SPI3*
|
||||
|
||||
define HAL_I2C_INTERNAL_MASK 2
|
||||
NODMA I2C*
|
||||
define STM32_I2C_USE_DMA FALSE
|
||||
|
||||
define RELAY2_PIN_DEFAULT 81 # Pit-1
|
||||
define RELAY3_PIN_DEFAULT 82 # PIN-EN
|
||||
define RELAY4_PIN_DEFAULT 83 # CAM-C
|
||||
|
||||
# Motor order Betaflight/X
|
||||
define HAL_FRAME_TYPE_DEFAULT 12
|
||||
|
||||
# USART1 (RX)
|
||||
# USART3 (ESC Telem)
|
||||
PD8 USART3_TX USART3 NODMA
|
||||
PD9 USART3_RX USART3 NODMA
|
||||
# UART4 (GPS)
|
||||
# UART5 (VTX)
|
||||
PB5 UART5_RX UART5 NODMA
|
||||
PB6 UART5_TX UART5 NODMA
|
||||
# USART6 (DJI FPV)
|
||||
# UART7
|
||||
# UART8
|
||||
PE0 UART8_RX UART8 NODMA
|
||||
PE1 UART8_TX UART8 NODMA
|
||||
|
||||
# Motors
|
||||
PB0 TIM3_CH3 TIM3 PWM(1) GPIO(50) BIDIR
|
||||
PB1 TIM3_CH4 TIM3 PWM(2) GPIO(51)
|
||||
PD12 TIM4_CH1 TIM4 PWM(3) GPIO(52) BIDIR
|
||||
PA0 TIM2_CH1 TIM2 PWM(5) GPIO(54) BIDIR
|
||||
PA2 TIM2_CH3 TIM2 PWM(7) GPIO(56) BIDIR
|
|
@ -21,6 +21,11 @@ FLASH_BOOTLOADER_LOAD_KB 128
|
|||
# order of UARTs (and USB)
|
||||
SERIAL_ORDER OTG1
|
||||
|
||||
# use last 2 pages for flash storage
|
||||
# H743 has 16 pages of 128k each
|
||||
STORAGE_FLASH_PAGE 14
|
||||
define HAL_STORAGE_SIZE 32768
|
||||
|
||||
# PA10 IO-debug-console
|
||||
PA11 OTG_FS_DM OTG1
|
||||
PA12 OTG_FS_DP OTG1
|
||||
|
|
Loading…
Reference in New Issue