mirror of https://github.com/ArduPilot/ardupilot
hwdef: add YJUAV_A6SE_H743 board support
This commit is contained in:
parent
6368ec4bd5
commit
f7dd6dec96
Binary file not shown.
File diff suppressed because it is too large
Load Diff
|
@ -0,0 +1,267 @@
|
|||
# A6SE_H743 Flight Controller
|
||||
|
||||
The A6SE_H743 flight controller is manufactured and sold by [YJUAV](http://www.yjuav.net).
|
||||
|
||||
## Features
|
||||
|
||||
- STM32H743 microcontroller
|
||||
- Onboard Flash: 2048Mbits
|
||||
- Two IMUs: ICM42688, ICM42688
|
||||
- Internal ITS8310 I2C magnetometer
|
||||
- Internal DPS310 SPI barometer
|
||||
- Internal RGB LED
|
||||
- microSD card slot port
|
||||
- 1 analog power ports
|
||||
- 5 UARTs and 1 USB ports
|
||||
- 3 I2C and 2 CAN ports
|
||||
- 11 PWM output ports
|
||||
- Safety switch port
|
||||
- External SPI port
|
||||
- Buzzer port
|
||||
- RC IN port
|
||||
|
||||
## Pinout
|
||||
![YJUAV_A6SE_H743 Board](YJUAV_A6SE_H743-pinout.jpg "YJUAV_A6SE_H743")
|
||||
|
||||
|
||||
## Connectors
|
||||
|
||||
**POWER ADC**
|
||||
|
||||
| Pin | Signal | Volt |
|
||||
| :--: | :-------------: | :---: |
|
||||
| 1 | VCC_IN | +5V |
|
||||
| 2 | VCC_IN | +5V |
|
||||
| 3 | BAT_CRRENT_ADC | +3.3V |
|
||||
| 4 | BAT_VOLTAGE_ADC | +3.3V |
|
||||
| 5 | GND | GND |
|
||||
| 6 | GND | GND |
|
||||
|
||||
**TELEM1**
|
||||
|
||||
| Pin | Signal | Volt |
|
||||
| :--: | :-----: | :---: |
|
||||
| 1 | VCC | +5V |
|
||||
| 2 | UART_TX2 | +3.3V |
|
||||
| 3 | UART_RX2 | +3.3V |
|
||||
| 4 | CTS | +3.3V |
|
||||
| 5 | RTS | +3.3V |
|
||||
| 6 | GND | GND |
|
||||
|
||||
**TELEM2**
|
||||
|
||||
| Pin | Signal | Volt |
|
||||
| :--: | :-----: | :---: |
|
||||
| 1 | VCC | +5V |
|
||||
| 2 | UART_TX6 | +3.3V |
|
||||
| 3 | UART_RX6 | +3.3V |
|
||||
| 4 | CTS | +3.3V |
|
||||
| 5 | RTS | +3.3V |
|
||||
| 6 | GND | GND |
|
||||
|
||||
**ADC**
|
||||
|
||||
| Pin | Signal | Volt |
|
||||
| :--: | :-----: | :---: |
|
||||
| 1 | VCC | +5V |
|
||||
| 2 | ADC_3V3 | +3.3V |
|
||||
| 3 | ADC_6V6 | +6.6V |
|
||||
| 4 | GND | GND |
|
||||
|
||||
**SPI**
|
||||
|
||||
| Pin | Signal | Volt |
|
||||
| :--: | :------: | :---: |
|
||||
| 1 | VCC | +5V |
|
||||
| 2 | SPI_SCK | +3.3V |
|
||||
| 3 | SPI_MISO | +3.3V |
|
||||
| 4 | SPI_MOSI | +3.3V |
|
||||
| 5 | SPI_CS | +3.3V |
|
||||
| 6 | GND | GND |
|
||||
|
||||
**I2C**
|
||||
|
||||
| Pin | Signal | Volt |
|
||||
| :--: | :-----: | :---: |
|
||||
| 1 | VCC | +5V |
|
||||
| 2 | I2C4_SCL | +3.3V |
|
||||
| 3 | I2C4_SDA | +3.3V |
|
||||
| 4 | GND | GND |
|
||||
|
||||
**CAN1**
|
||||
|
||||
| Pin | Signal | Volt |
|
||||
| :--: | :----: | :---: |
|
||||
| 1 | VCC | +5V |
|
||||
| 2 | CAN1_P | +3.3V |
|
||||
| 3 | CAN1_N | +3.3V |
|
||||
| 4 | GND | GND |
|
||||
|
||||
**CAN2**
|
||||
|
||||
| Pin | Signal | Volt |
|
||||
| :--: | :----: | :---: |
|
||||
| 1 | VCC | +5V |
|
||||
| 2 | CAN2_P | +3.3V |
|
||||
| 3 | CAN2_N | +3.3V |
|
||||
| 4 | GND | GND |
|
||||
|
||||
**GPS1**
|
||||
|
||||
| Pin | Signal | Volt |
|
||||
| :--: | :-----: | :---: |
|
||||
| 1 | VCC | +5V |
|
||||
| 2 | UART_TX3 | +3.3V |
|
||||
| 3 | UART_RX3 | +3.3V |
|
||||
| 4 | I2C2_SCL | +3.3V |
|
||||
| 5 | I2C2_SDA | +3.3V |
|
||||
| 6 | GND | GND |
|
||||
|
||||
**GPS2&SAFETY**
|
||||
|
||||
| Pin | Signal | Volt |
|
||||
| :--: | :-----------: | :---: |
|
||||
| 1 | VCC | +5V |
|
||||
| 2 | UART_TX1 | +3.3V |
|
||||
| 3 | UART_RX1 | +3.3V |
|
||||
| 4 | I2C3_SCL | +3.3V |
|
||||
| 5 | I2C3_SDA | +3.3V |
|
||||
| 6 | SAFETY_SW | +3.3V |
|
||||
| 7 | SAFETY_SW_LED | +3.3V |
|
||||
| 8 | 3V3_OUT | +3.3V |
|
||||
| 9 | BUZZER | +3.3V |
|
||||
| 10 | GND | GND |
|
||||
|
||||
**DEBUG**
|
||||
|
||||
| Pin | Signal | Volt |
|
||||
| :--: | :----: | :---: |
|
||||
| 1 | VCC | +5V |
|
||||
| 2 | UART_TX7 | +3.3V |
|
||||
| 3 | UART_RX7 | +3.3V |
|
||||
| 4 | SWDIO | +3.3V |
|
||||
| 5 | SWCLK | +3.3V |
|
||||
| 6 | GND | GND |
|
||||
|
||||
**SAFETY**
|
||||
|
||||
| Pin | Signal | Volt |
|
||||
| :--: | :-----------: | :---: |
|
||||
| 1 | 3V3_OUT | +3.3V |
|
||||
| 2 | SAFETY_SW | +3.3V |
|
||||
| 3 | SAFETY_SW_LED | +3.3V |
|
||||
| 4 | SBUS_OUT | +3.3V |
|
||||
| 5 | RSSI | +3.3V |
|
||||
| 6 | GND | GND |
|
||||
|
||||
**USB EX**
|
||||
|
||||
| Pin | Signal | Volt |
|
||||
| :--: | :----: | :---: |
|
||||
| 1 | VCC_IN | +5V |
|
||||
| 2 | DM | +3.3V |
|
||||
| 3 | DP | +3.3V |
|
||||
| 4 | GND | GND |
|
||||
|
||||
## UART Mapping
|
||||
|
||||
- SERIAL0 -> USB (OTG1)
|
||||
- SERIAL1 -> USART2 (Telem1)
|
||||
- SERIAL2 -> USART6 (Telem2)
|
||||
- SERIAL3 -> USART3 (GPS1), NODMA
|
||||
- SERIAL4 -> USART1 (GPS2), NODMA
|
||||
- SERIAL5 -> UART8 (USER) TX only, normally used for SBUS_OUT with protocol change
|
||||
- SERIAL6 -> UART7 (USER/Debug), NODMA
|
||||
- SERIAL7 -> USB2 (OTG2)
|
||||
|
||||
## RC Input
|
||||
|
||||
The RCIN pin is mapped to a timer input instead of the UART, and can be used for all ArduPilot supported receiver protocols, except CRSF/ELRS and SRXL2 which require a true UART connection. However, FPort, when connected in this manner, can provide RC without telemetry.
|
||||
|
||||
To allow CRSF and embedded telemetry available in Fport, CRSF, and SRXL2 receivers, a full UART must be used. For example, UART1 can have its protocol changed from the default GPS protocol for GPS2 to RX input protocol:
|
||||
|
||||
With this option, SERIAL4_PROTOCOL must be set to “23”, and:
|
||||
|
||||
PPM is not supported.
|
||||
|
||||
SBUS/DSM/SRXL connects to the RX1 pin.
|
||||
|
||||
FPort requires connection to TX1 and RX1. See FPort Receivers.
|
||||
|
||||
CRSF also requires a TX1 connection, in addition to RX1, and automatically provides telemetry.
|
||||
|
||||
SRXL2 requires a connection to TX1 and automatically provides telemetry. Set SERIAL4_OPTIONS to “4”.
|
||||
|
||||
Any UART can be used for RC system connections in ArduPilot also, and is compatible with all protocols except PPM. See Radio Control Systems for details.
|
||||
|
||||
## PWM Output
|
||||
|
||||
The A6SE_H743 supports up to 11 PWM outputs,support all PWM protocols as well as DShot. All 11 PWM outputs have GND on the bottom row, 5V on the middle row and signal on the top row.
|
||||
|
||||
The 11 PWM outputs are in 3 groups:
|
||||
|
||||
- PWM 1, 2, 3 and 4 in group1
|
||||
- PWM 5, 6, 7 and 8 in group2
|
||||
- PWM 9, 10, 11 in group3
|
||||
|
||||
Channels 1-8 support bi-directional Dshot.
|
||||
Channels within the same group need to use the same output rate. If any channel in a group uses DShot, then all channels in that group need to use DShot.
|
||||
|
||||
## GPIOs
|
||||
|
||||
All 11 PWM channels can be used for GPIO functions (relays, buttons, RPM etc).
|
||||
|
||||
The pin numbers for these PWM channels in ArduPilot are shown below:
|
||||
|
||||
| PWM Channels | Pin | PWM Channels | Pin |
|
||||
| ------------ | ---- | ------------ | ---- |
|
||||
| PWM1 | 50 | PWM8 | 57 |
|
||||
| PWM2 | 51 | PWM9 | 58 |
|
||||
| PWM3 | 52 | PWM10 | 59 |
|
||||
| PWM4 | 53 | PWM11 | 60 |
|
||||
| PWM5 | 54 | | |
|
||||
| PWM6 | 55 | | |
|
||||
| PWM7 | 56 | | |
|
||||
|
||||
## Analog inputs
|
||||
|
||||
The A6SE_H743 flight controller has 5 analog inputs
|
||||
|
||||
- ADC Pin4 -> Battery Current
|
||||
- ADC Pin2 -> Battery Voltage
|
||||
- ADC Pin8 -> ADC 3V3 Sense
|
||||
- ADC Pin10 -> ADC 6V6 Sense
|
||||
- ADC Pin11 -> RSSI voltage monitoring
|
||||
|
||||
## Battery Monitor Configuration
|
||||
|
||||
The board has voltage and current sensor inputs on the POWER_ADC connector.
|
||||
|
||||
The correct battery setting parameters are:
|
||||
|
||||
Enable Battery monitor.
|
||||
|
||||
BATT_MONITOR =4
|
||||
|
||||
Then reboot.
|
||||
|
||||
BATT_VOLT_PIN 2
|
||||
|
||||
BATT_CURR_PIN 4
|
||||
|
||||
BATT_VOLT_MULT 21.0 (may need adjustment if supplied monitor is not used)
|
||||
|
||||
BATT_AMP_PERVLT 34.0 (may need adjustment if supplied monitor is not used)
|
||||
|
||||
## Build the FC
|
||||
|
||||
./waf configure --board=YJUAV_A6SE_H743
|
||||
./waf copter
|
||||
|
||||
The compiled firmware is located in folder **"build/YJUAV_A6SE_H743/bin/arducopter.apj"**.
|
||||
|
||||
|
||||
## Loading Firmware
|
||||
|
||||
The A6SE_H743 flight controller comes pre-installed with an ArduPilot compatible bootloader, allowing the loading of *.apj firmware files with any ArduPilot compatible ground station.
|
||||
|
Binary file not shown.
After Width: | Height: | Size: 178 KiB |
|
@ -0,0 +1,5 @@
|
|||
# setup the heater temperature to 45 degree
|
||||
BRD_HEAT_TARG 45
|
||||
|
||||
CAN_P1_DRIVER 1
|
||||
|
|
@ -0,0 +1,51 @@
|
|||
# hw definition file for processing by chibios_hwdef.py
|
||||
# for YJUAV_A6SE_H743 board
|
||||
|
||||
# MCU class and specific type
|
||||
MCU STM32H7xx STM32H743xx
|
||||
|
||||
# crystal frequency
|
||||
OSCILLATOR_HZ 16000000
|
||||
|
||||
# board ID for firmware load
|
||||
APJ_BOARD_ID 1141
|
||||
|
||||
FLASH_SIZE_KB 2048
|
||||
|
||||
# bootloader is installed at zero offset
|
||||
FLASH_RESERVE_START_KB 0
|
||||
|
||||
# the location where the bootloader will put the firmware
|
||||
# the H743 has 128k sectors
|
||||
FLASH_BOOTLOADER_LOAD_KB 128
|
||||
|
||||
# order of UARTs (and USB). Allow bootloading on USB and Debug
|
||||
SERIAL_ORDER OTG1 UART7
|
||||
|
||||
# UART7 DEBUG
|
||||
PE7 UART7_RX UART7 NODMA
|
||||
PE8 UART7_TX UART7 NODMA
|
||||
define BOOTLOADER_DEBUG SD7
|
||||
|
||||
# USB
|
||||
PA11 OTG_FS_DM OTG1
|
||||
PA12 OTG_FS_DP OTG1
|
||||
|
||||
PA13 JTMS-SWDIO SWD
|
||||
PA14 JTCK-SWCLK SWD
|
||||
|
||||
PE15 LED_RED OUTPUT OPENDRAIN HIGH # red
|
||||
PD10 LED_BOOTLOADER OUTPUT OPENDRAIN HIGH # green
|
||||
PG0 LED_ACTIVITY OUTPUT OPENDRAIN HIGH # blue
|
||||
define HAL_LED_ON 0
|
||||
|
||||
# Add CS pins to ensure they are high in bootloader
|
||||
PE4 IMU1_CS CS
|
||||
PA0 IMU2_CS CS
|
||||
PE10 FRAM_CS CS
|
||||
PE9 BAROMETER_CS CS
|
||||
PE3 COMPASS_CS CS
|
||||
PC15 RESERVE_CS CS
|
||||
|
||||
# Extra SPI CS
|
||||
PE5 EXT_CS CS
|
|
@ -0,0 +1,241 @@
|
|||
# hw definition file for processing by chibios_hwdef.py for YJUAV_A6SE_H743
|
||||
|
||||
# MCU class and specific type
|
||||
MCU STM32H7xx STM32H743xx
|
||||
|
||||
# crystal frequency
|
||||
OSCILLATOR_HZ 16000000
|
||||
|
||||
# board ID for firmware load
|
||||
APJ_BOARD_ID 1141
|
||||
|
||||
env OPTIMIZE -O2
|
||||
|
||||
# ChibiOS system timer
|
||||
STM32_ST_USE_TIMER 5
|
||||
|
||||
FLASH_SIZE_KB 2048
|
||||
|
||||
# bootloader takes first sector
|
||||
FLASH_RESERVE_START_KB 128
|
||||
|
||||
# order of UARTs (and USB)
|
||||
SERIAL_ORDER OTG1 USART2 USART6 USART3 USART1 UART8 UART7 OTG2
|
||||
|
||||
# now we define the pins that USB is connected on
|
||||
PA11 OTG_FS_DM OTG1
|
||||
PA12 OTG_FS_DP OTG1
|
||||
|
||||
# USART2 TELEM1
|
||||
PD6 USART2_RX USART2
|
||||
PD5 USART2_TX USART2
|
||||
PD3 USART2_CTS USART2
|
||||
PD4 USART2_RTS USART2
|
||||
|
||||
# USART6 TELEM2
|
||||
PC7 USART6_RX USART6
|
||||
PC6 USART6_TX USART6
|
||||
PG13 USART6_CTS USART6
|
||||
PG8 USART6_RTS USART6
|
||||
|
||||
# USART3 GPS1
|
||||
PD9 USART3_RX USART3 NODMA
|
||||
PD8 USART3_TX USART3 NODMA
|
||||
|
||||
# USART1 GPS2
|
||||
PB7 USART1_RX USART1 NODMA
|
||||
PA9 USART1_TX USART1 NODMA
|
||||
|
||||
# SBUS, DSM port
|
||||
PE0 UART8_RX UART8
|
||||
PE1 UART8_TX UART8
|
||||
|
||||
# UART7 DEBUG
|
||||
PE7 UART7_RX UART7 NODMA
|
||||
PE8 UART7_TX UART7 NODMA
|
||||
|
||||
# these are the pins for SWD debugging with a STlinkv2 or black-magic probe
|
||||
PA13 JTMS-SWDIO SWD
|
||||
PA14 JTCK-SWCLK SWD
|
||||
|
||||
# SPI1 -IMU1
|
||||
PB3 SPI1_SCK SPI1
|
||||
PB4 SPI1_MISO SPI1
|
||||
PD7 SPI1_MOSI SPI1
|
||||
|
||||
# SPI6 -IMU2 -IMU3
|
||||
PA5 SPI6_SCK SPI6
|
||||
PA6 SPI6_MISO SPI6
|
||||
PA7 SPI6_MOSI SPI6
|
||||
|
||||
# SPI5
|
||||
PF7 SPI5_SCK SPI5
|
||||
PF8 SPI5_MISO SPI5
|
||||
PF9 SPI5_MOSI SPI5
|
||||
|
||||
# SPI4 -Extra SPI
|
||||
PE12 SPI4_SCK SPI4
|
||||
PE13 SPI4_MISO SPI4
|
||||
PE6 SPI4_MOSI SPI4
|
||||
|
||||
# sensors cs
|
||||
PE4 IMU1_CS CS
|
||||
PA0 IMU2_CS CS
|
||||
PE10 FRAM_CS CS
|
||||
PE9 BAROMETER1_CS CS
|
||||
PE3 BAROMETER2_CS CS
|
||||
PC15 RESERVE_CS CS
|
||||
|
||||
# Extra SPI CS
|
||||
PE5 EXT_CS CS
|
||||
|
||||
# I2C buses
|
||||
PB8 I2C1_SCL I2C1
|
||||
PB9 I2C1_SDA I2C1
|
||||
|
||||
PB10 I2C2_SCL I2C2
|
||||
PB11 I2C2_SDA I2C2
|
||||
|
||||
PH7 I2C3_SCL I2C3
|
||||
PH8 I2C3_SDA I2C3
|
||||
|
||||
PF14 I2C4_SCL I2C4
|
||||
PF15 I2C4_SDA I2C4
|
||||
|
||||
# order of I2C buses
|
||||
I2C_ORDER I2C1 I2C2 I2C3 I2C4
|
||||
|
||||
NODMA I2C*
|
||||
define STM32_I2C_USE_DMA FALSE
|
||||
define HAL_I2C_INTERNAL_MASK 1
|
||||
|
||||
# PWM channels
|
||||
PA15 TIM2_CH1 TIM2 PWM(1) GPIO(50) BIDIR
|
||||
PA1 TIM2_CH2 TIM2 PWM(2) GPIO(51)
|
||||
PA2 TIM2_CH3 TIM2 PWM(3) GPIO(52) BIDIR
|
||||
PA3 TIM2_CH4 TIM2 PWM(4) GPIO(53)
|
||||
PA8 TIM1_CH1 TIM1 PWM(5) GPIO(54) BIDIR
|
||||
PE11 TIM1_CH2 TIM1 PWM(6) GPIO(55)
|
||||
PA10 TIM1_CH3 TIM1 PWM(7) GPIO(56) BIDIR
|
||||
PE14 TIM1_CH4 TIM1 PWM(8) GPIO(57)
|
||||
PB5 TIM3_CH2 TIM3 PWM(9) GPIO(58)
|
||||
PB0 TIM3_CH3 TIM3 PWM(10) GPIO(59)
|
||||
PB1 TIM3_CH4 TIM3 PWM(11) GPIO(60)
|
||||
|
||||
# PWM output for buzzer
|
||||
PD14 TIM4_CH3 TIM4 GPIO(77) ALARM
|
||||
|
||||
# RC input
|
||||
PI7 TIM8_CH3 TIM8 RCININT PULLUP LOW
|
||||
|
||||
# Analog in
|
||||
PC4 BATT_CURRENT_SENS ADC1 SCALE(1)
|
||||
PF11 BATT_VOLTAGE_SENS ADC1 SCALE(1)
|
||||
|
||||
# Analog sys 5v
|
||||
PF12 VDD_5V_SENS ADC1 SCALE(2)
|
||||
|
||||
# ADC3.3/ADC6.6
|
||||
PC5 SPARE1_ADC1 ADC1 SCALE(1)
|
||||
PC0 SPARE2_ADC1 ADC1 SCALE(2)
|
||||
|
||||
PC1 RSSI_IN ADC1 SCALE(1)
|
||||
|
||||
PC3 FMU_SERVORAIL_VCC_SENS ADC1 SCALE(3)
|
||||
|
||||
# CAN bus
|
||||
PD0 CAN1_RX CAN1
|
||||
PD1 CAN1_TX CAN1
|
||||
|
||||
PB12 CAN2_RX CAN2
|
||||
PB13 CAN2_TX CAN2
|
||||
|
||||
# GPIOs
|
||||
PC13 HEATER_EN OUTPUT LOW GPIO(80)
|
||||
define HAL_HEATER_GPIO_PIN 80
|
||||
define HAL_HAVE_IMU_HEATER 1
|
||||
|
||||
# define default battery setup
|
||||
define HAL_BATT_VOLT_PIN 2
|
||||
define HAL_BATT_CURR_PIN 4
|
||||
define HAL_BATT_VOLT_SCALE 21
|
||||
define HAL_BATT_CURR_SCALE 34
|
||||
define HAL_BATT_MONITOR_DEFAULT 4
|
||||
|
||||
#analog rssi pin (also could be used as analog airspeed input)
|
||||
# PC1
|
||||
define BOARD_RSSI_ANA_PIN 11
|
||||
|
||||
# enable pins
|
||||
PC14 VDD_3V3_SENSORS_EN OUTPUT LOW
|
||||
|
||||
# red LED marked as B/E
|
||||
PE15 LED_R1 OUTPUT OPENDRAIN HIGH GPIO(0)
|
||||
PD10 LED_G1 OUTPUT OPENDRAIN LOW GPIO(1)
|
||||
PG0 LED_B1 OUTPUT OPENDRAIN HIGH GPIO(2)
|
||||
|
||||
define HAL_GPIO_A_LED_PIN 0
|
||||
define HAL_GPIO_B_LED_PIN 1
|
||||
define HAL_GPIO_C_LED_PIN 2
|
||||
|
||||
define HAL_GPIO_LED_ON 0
|
||||
define HAL_GPIO_LED_OFF 1
|
||||
|
||||
# use pixracer style 3-LED indicators
|
||||
define HAL_HAVE_PIXRACER_LED
|
||||
|
||||
# allow to have have a dedicated safety switch pin
|
||||
define HAL_HAVE_SAFETY_SWITCH 1
|
||||
PB15 LED_SAFETY OUTPUT
|
||||
PA4 SAFETY_IN INPUT PULLDOWN
|
||||
|
||||
# SPI devices
|
||||
SPIDEV imu1 SPI1 DEVID1 IMU1_CS MODE3 2*MHZ 8*MHZ
|
||||
SPIDEV imu2 SPI6 DEVID1 IMU2_CS MODE3 2*MHZ 8*MHZ
|
||||
SPIDEV ramtron SPI5 DEVID1 FRAM_CS MODE3 8*MHZ 8*MHZ
|
||||
SPIDEV dps310 SPI5 DEVID3 BAROMETER1_CS MODE3 5*MHZ 5*MHZ
|
||||
SPIDEV ms5611 SPI5 DEVID3 BAROMETER2_CS MODE3 5*MHZ 5*MHZ
|
||||
|
||||
# IMU1
|
||||
IMU Invensense SPI:imu1 ROTATION_NONE
|
||||
IMU Invensensev3 SPI:imu1 ROTATION_NONE
|
||||
|
||||
# IMU2
|
||||
IMU Invensense SPI:imu2 ROTATION_NONE
|
||||
IMU Invensensev3 SPI:imu2 ROTATION_NONE
|
||||
|
||||
define HAL_DEFAULT_INS_FAST_SAMPLE 3
|
||||
|
||||
# baro
|
||||
BARO DPS310 SPI:dps310
|
||||
BARO MS56XX SPI:ms5611
|
||||
BARO ICP201XX I2C:0:0x64
|
||||
|
||||
# compass
|
||||
define HAL_COMPASS_DISABLE_IST8310_INTERNAL_PROBE
|
||||
define HAL_PROBE_EXTERNAL_I2C_COMPASSES
|
||||
|
||||
COMPASS IST8310 I2C:ALL_EXTERNAL:0x0E true ROTATION_ROLL_180_YAW_90
|
||||
COMPASS IST8310 I2C:0:0x0E false ROTATION_YAW_180
|
||||
|
||||
# microSD support
|
||||
PC8 SDMMC1_D0 SDMMC1
|
||||
PC9 SDMMC1_D1 SDMMC1
|
||||
PC10 SDMMC1_D2 SDMMC1
|
||||
PC11 SDMMC1_D3 SDMMC1
|
||||
PC12 SDMMC1_CK SDMMC1
|
||||
PD2 SDMMC1_CMD SDMMC1
|
||||
|
||||
# enable FAT filesystem support (needs a microSD defined via SDMMC)
|
||||
define HAL_OS_FATFS_IO 1
|
||||
|
||||
define HAL_BOARD_LOG_DIRECTORY "/APM/LOGS"
|
||||
define HAL_BOARD_TERRAIN_DIRECTORY "/APM/TERRAIN"
|
||||
|
||||
# enable RAMTROM parameter storage
|
||||
define HAL_STORAGE_SIZE 32768
|
||||
define HAL_WITH_RAMTRON 1
|
||||
|
||||
DMA_PRIORITY SPI1* SPI6* TIM*UP*
|
||||
DMA_NOSHARE SPI1* SPI6* TIM*UP*
|
||||
|
Loading…
Reference in New Issue