mirror of https://github.com/ArduPilot/ardupilot
291 lines
7.6 KiB
Plaintext
291 lines
7.6 KiB
Plaintext
# hw definition file for processing by chibios_hwdef.py
|
|
# for H757
|
|
|
|
# MCU class and specific type
|
|
MCU STM32H7xx STM32H757xx
|
|
|
|
# USB setup
|
|
USB_VENDOR 0x2DAE # ONLY FOR USE BY HEX! NOBODY ELSE
|
|
USB_PRODUCT 0x1059
|
|
USB_STRING_MANUFACTURER "CubePilot"
|
|
USB_STRING_PRODUCT "CubeRed"
|
|
|
|
define CORE_CM7
|
|
define SMPS_PWR
|
|
|
|
# crystal frequency
|
|
OSCILLATOR_HZ 24000000
|
|
|
|
# board ID for firmware load
|
|
APJ_BOARD_ID 1069
|
|
|
|
FLASH_SIZE_KB 2048
|
|
|
|
# bootloader is installed at zero offset
|
|
FLASH_RESERVE_START_KB 128
|
|
|
|
# the location where the bootloader will put the firmware
|
|
# the H743 has 128k sectors
|
|
FLASH_BOOTLOADER_LOAD_KB 128
|
|
|
|
define HAL_LED_ON 0
|
|
|
|
# Enable FAT filesystem support (needs a microSD defined via SDMMC).
|
|
define HAL_OS_FATFS_IO 1
|
|
|
|
# Setup the IMU heater
|
|
define HAL_HAVE_IMU_HEATER 1
|
|
define HAL_IMU_TEMP_DEFAULT 45
|
|
define HAL_IMUHEAT_P_DEFAULT 50
|
|
define HAL_IMUHEAT_I_DEFAULT 0.07
|
|
define HAL_IMU_TEMP_MARGIN_LOW_DEFAULT 5
|
|
|
|
|
|
# supports upto 8MBits/s
|
|
CANFD_SUPPORTED 8
|
|
|
|
STM32_ST_USE_TIMER 12
|
|
|
|
define CH_CFG_ST_RESOLUTION 16
|
|
|
|
# use last 2 pages for flash storage
|
|
# H757 has 16 pages of 128k each
|
|
STORAGE_FLASH_PAGE 14
|
|
define HAL_STORAGE_SIZE 32768
|
|
|
|
# ADC setup
|
|
PF11 BATT_VOLTAGE_SENS ADC1 SCALE(1) ANALOG(14)
|
|
PC0 BATT_CURRENT_SENS ADC1 SCALE(1) ANALOG(15)
|
|
|
|
PB1 AUX_POWER ADC2 SCALE(1) ANALOG(13) # AUX Volt
|
|
PF12 AUX_ADC2 ADC1 SCALE(1) ANALOG(4) # AUX Curr
|
|
|
|
define HAL_BATT_VOLT_PIN 14
|
|
define HAL_BATT_CURR_PIN 15
|
|
define HAL_BATT2_VOLT_PIN 13
|
|
define HAL_BATT2_CURR_PIN 4
|
|
define HAL_BATT_VOLT_SCALE 12.02
|
|
define HAL_BATT_CURR_SCALE 39.877
|
|
|
|
PF13 VDD_5V_SENS ADC2 SCALE(2) ANALOG(18)
|
|
|
|
# And the analog input for airspeed (rarely used these days).
|
|
PF3 PRESSURE_SENS ADC3 SCALE(2) ANALOG(8)
|
|
PC3 FMU_SERVORAIL_VCC_SENS ADC3 SCALE(3) ANALOG(9)
|
|
|
|
# CAN config
|
|
PE10 GPIOCAN1_TERM OUTPUT HIGH
|
|
PG4 GPIOCAN2_TERM OUTPUT HIGH
|
|
|
|
PB8 CAN1_RX CAN1
|
|
PB9 CAN1_TX CAN1
|
|
PB5 CAN2_RX CAN2
|
|
PB6 CAN2_TX CAN2
|
|
|
|
|
|
# SPI1
|
|
PE13 BARO_0_CS CS
|
|
PE9 ICM42688_0_CS CS
|
|
PB3 SPI1_SCK SPI1
|
|
PB4 SPI1_MISO SPI1
|
|
PD7 SPI1_MOSI SPI1
|
|
|
|
# SPI2
|
|
PD15 RM3100_CS CS
|
|
PD14 ICM42688_1_CS CS
|
|
PA9 SPI2_SCK SPI2
|
|
PB14 SPI2_MISO SPI2
|
|
PB15 SPI2_MOSI SPI2
|
|
|
|
# SPI4
|
|
PF5 ICM_2_CS CS
|
|
PC2 BARO_1_CS CS
|
|
PE12 SPI4_SCK SPI4
|
|
PE5 SPI4_MISO SPI4
|
|
PE6 SPI4_MOSI SPI4
|
|
|
|
# Sensors
|
|
SPIDEV icm42688_0 SPI1 DEVID1 ICM42688_0_CS MODE3 2*MHZ 8*MHZ
|
|
SPIDEV ms5611_0 SPI1 DEVID2 BARO_0_CS MODE3 20*MHZ 20*MHZ
|
|
|
|
SPIDEV icm42688_1 SPI2 DEVID1 ICM42688_1_CS MODE3 2*MHZ 8*MHZ
|
|
SPIDEV rm3100 SPI2 DEVID2 RM3100_CS MODE3 1*MHZ 1*MHZ
|
|
|
|
SPIDEV icm20649 SPI4 DEVID1 ICM_2_CS MODE3 4*MHZ 8*MHZ
|
|
# alternative to icm20649
|
|
SPIDEV icm45686 SPI4 DEVID1 ICM_2_CS MODE3 2*MHZ 8*MHZ
|
|
SPIDEV ms5611_1 SPI4 DEVID2 BARO_1_CS MODE3 20*MHZ 20*MHZ
|
|
|
|
IMU Invensensev3 SPI:icm42688_1 ROTATION_YAW_90
|
|
IMU Invensensev3 SPI:icm42688_0 ROTATION_PITCH_180_YAW_270
|
|
IMU Invensensev2 SPI:icm20649 ROTATION_PITCH_180
|
|
IMU Invensensev3 SPI:icm45686 ROTATION_YAW_180
|
|
|
|
BARO MS56XX SPI:ms5611_0
|
|
BARO MS56XX SPI:ms5611_1
|
|
|
|
COMPASS RM3100 SPI:rm3100 false ROTATION_YAW_270
|
|
|
|
CHECK_ICM20649 spi_check_register_inv2("icm20649", INV2REG_WHOAMI, INV2_WHOAMI_ICM20649)
|
|
CHECK_ICM45686_2 spi_check_register("icm45686", INV3REG_456_WHOAMI, INV3_WHOAMI_ICM45686)
|
|
|
|
CHECK_ICM42688_0 spi_check_register("icm42688_0", INV3REG_WHOAMI, INV3_WHOAMI_ICM42688)
|
|
CHECK_ICM45686_0 spi_check_register("icm42688_0", INV3REG_456_WHOAMI, INV3_WHOAMI_ICM45686)
|
|
|
|
CHECK_ICM42688_1 spi_check_register("icm42688_1", INV3REG_WHOAMI, INV3_WHOAMI_ICM42688)
|
|
CHECK_ICM45686_1 spi_check_register("icm42688_1", INV3REG_456_WHOAMI, INV3_WHOAMI_ICM45686)
|
|
|
|
CHECK_MS5611_0 check_ms5611("ms5611_0")
|
|
CHECK_MS5611_1 check_ms5611("ms5611_1")
|
|
|
|
|
|
CHECK_IMU0_PRESENT $CHECK_ICM20649 || $CHECK_ICM45686_2
|
|
CHECK_IMU1_PRESENT $CHECK_ICM42688_0 || $CHECK_ICM45686_0
|
|
CHECK_IMU2_PRESENT $CHECK_ICM42688_1 || $CHECK_ICM45686_1
|
|
CHECK_BARO0_PRESENT $CHECK_MS5611_0
|
|
CHECK_BARO1_PRESENT $CHECK_MS5611_1
|
|
|
|
BOARD_VALIDATE $CHECK_IMU0_PRESENT $CHECK_BARO0_PRESENT $CHECK_IMU1_PRESENT $CHECK_BARO1_PRESENT $CHECK_IMU2_PRESENT
|
|
|
|
define HAL_CHIBIOS_ARCH_FMUV3 1
|
|
|
|
define BOARD_TYPE_DEFAULT 3
|
|
|
|
# MCO output
|
|
PA8 RCC_MCO_1 OUTPUT LOW
|
|
|
|
# I2C
|
|
PF0 I2C2_SDA I2C2
|
|
PF1 I2C2_SCL I2C2
|
|
PF14 I2C4_SCL I2C4
|
|
PF15 I2C4_SDA I2C4
|
|
I2C_ORDER I2C2 I2C4
|
|
|
|
# Ethernet
|
|
PC1 ETH_MDC ETH1
|
|
PA2 ETH_MDIO ETH1
|
|
PC4 ETH_RMII_RXD0 ETH1
|
|
PC5 ETH_RMII_RXD1 ETH1
|
|
PB12 ETH_RMII_TXD0 ETH1
|
|
PB13 ETH_RMII_TXD1 ETH1
|
|
PB11 ETH_RMII_TX_EN ETH1
|
|
PA7 ETH_RMII_CRS_DV ETH1
|
|
PA1 ETH_RMII_REF_CLK ETH1
|
|
|
|
define BOARD_PHY_ID MII_LAN8720_ID
|
|
define BOARD_PHY_RMII
|
|
|
|
# Refer to https://maclookup.app/vendors/cubepilot-pty-ltd
|
|
# Note, lower 3 bytes (ADDR3,4,5) will be replaced with the platform UUID
|
|
define AP_NETWORKING_DEFAULT_MAC_ADDR "A8:B0:28:00:00:00"
|
|
|
|
# RCIN
|
|
PB7 TIM4_CH2 TIM4 RCININT PULLDOWN
|
|
|
|
# QUADSPI
|
|
PD11 QUADSPI_BK1_IO0 QUADSPI1
|
|
PD12 QUADSPI_BK1_IO1 QUADSPI1
|
|
PE2 QUADSPI_BK1_IO2 QUADSPI1
|
|
PD13 QUADSPI_BK1_IO3 QUADSPI1
|
|
PB10 QUADSPI_BK1_NCS QUADSPI1
|
|
PB2 QUADSPI_CLK QUADSPI1
|
|
|
|
# SDMMC
|
|
PC10 SDMMC1_D2 SDMMC1
|
|
PC11 SDMMC1_D3 SDMMC1
|
|
PC12 SDMMC1_CK SDMMC1
|
|
PC8 SDMMC1_D0 SDMMC1
|
|
PC9 SDMMC1_D1 SDMMC1
|
|
PD2 SDMMC1_CMD SDMMC1
|
|
|
|
# USB
|
|
PA11 OTG_FS_DM OTG1
|
|
PA12 OTG_FS_DP OTG1
|
|
|
|
# SWD
|
|
PA13 JTMS-SWDIO SWD
|
|
PA14 JTCK-SWCLK SWD
|
|
|
|
|
|
# GPIO
|
|
|
|
PG5 FMU_LED_AMBER OUTPUT HIGH OPENDRAIN GPIO(0)
|
|
|
|
# Power flag pins: these tell the MCU the status of the various power
|
|
# supplies that are available. The pin names need to exactly match the
|
|
# names used in AnalogIn.cpp.
|
|
PE15 VDD_BRICK_nVALID INPUT PULLUP
|
|
PE4 VDD_BRICK2_nVALID INPUT PULLUP
|
|
PF4 VDD_5V_HIPOWER_nOC INPUT PULLUP
|
|
PD10 VDD_5V_PERIPH_nOC INPUT PULLUP
|
|
|
|
|
|
# This is the pin to enable the sensors rail. It can be used to power
|
|
# cycle sensors to recover them in case there are problems with power on
|
|
# timing affecting sensor stability. We pull it LOW on startup, which
|
|
# means sensors off, then it is pulled HIGH in peripheral_power_enable()
|
|
PG0 VDD_3V3_SENSORS_EN OUTPUT LOW
|
|
|
|
# This defines an output pin which will default to output HIGH. It is
|
|
# a pin that enables peripheral power on this board. It starts in the
|
|
# off state, then is pulled low to enable peripherals in
|
|
# peripheral_power_enable()
|
|
PF2 nVDD_5V_PERIPH_EN OUTPUT LOW
|
|
|
|
PA0 TIM5_CH1 TIM5 GPIO(79) ALARM
|
|
|
|
PE3 VBUS_nVALID INPUT PULLUP
|
|
|
|
# upper
|
|
PG2 HEATER_EN OUTPUT LOW GPIO(81)
|
|
# lower
|
|
# PG1 HEATER_EN OUTPUT LOW GPIO(80)
|
|
|
|
define HAL_HEATER_GPIO_PIN 81
|
|
# define HAL_HEATER_GPIO_PIN2 80
|
|
|
|
# Timer
|
|
PE11 TIM1_CH2 TIM1 PWM(1) GPIO(50) BIDIR
|
|
PE14 TIM1_CH4 TIM1 PWM(2) GPIO(51) BIDIR
|
|
PA15 TIM2_CH1 TIM2 PWM(3) GPIO(52) BIDIR
|
|
PA3 TIM2_CH4 TIM2 PWM(4) GPIO(53) BIDIR
|
|
PA6 TIM3_CH1 TIM3 PWM(5) GPIO(54) BIDIR
|
|
PB0 TIM3_CH3 TIM3 PWM(6) GPIO(55) BIDIR
|
|
|
|
# UART
|
|
PD1 UART4_TX UART4
|
|
PD0 UART4_RX UART4
|
|
|
|
PE0 UART8_RX UART8
|
|
PE1 UART8_TX UART8
|
|
|
|
PD3 USART2_CTS USART2
|
|
PD4 USART2_RTS USART2
|
|
PD5 USART2_TX USART2
|
|
PD6 USART2_RX USART2
|
|
|
|
PD8 USART3_TX USART3
|
|
PD9 USART3_RX USART3
|
|
|
|
PC6 USART6_TX USART6
|
|
PC7 USART6_RX USART6
|
|
|
|
PG15 USART6_CTS USART6
|
|
PG8 USART6_RTS USART6
|
|
|
|
# primary <-> secondary
|
|
PE7 UART7_RX UART7
|
|
PE8 UART7_TX UART7
|
|
|
|
# order of UARTs (and USB)
|
|
SERIAL_ORDER OTG1 USART2 USART6 USART3 UART4 UART8 EMPTY UART7
|
|
|
|
EXT_FLASH_SIZE_MB 32
|
|
INT_FLASH_PRIMARY 1
|
|
|
|
# forward Serial traffic from USB OTG2 to Serial7(UART7)
|
|
define HAL_FORWARD_OTG2_SERIAL 7
|
|
define HAL_HAVE_DUAL_USB_CDC 1
|
|
define DEFAULT_SERIAL7_PROTOCOL SerialProtocol_MAVLink2
|
|
define DEFAULT_SERIAL7_BAUD 2000000
|