mirror of https://github.com/ArduPilot/ardupilot
105 lines
2.2 KiB
Plaintext
105 lines
2.2 KiB
Plaintext
# hw definition file for processing by chibios_hwdef.py
|
|
# for H757
|
|
|
|
# MCU class and specific type
|
|
MCU STM32H7xx STM32H757xx
|
|
|
|
|
|
define CORE_CM7
|
|
define SMPS_PWR
|
|
|
|
# board ID for firmware load
|
|
APJ_BOARD_ID 1079
|
|
|
|
# setup build for a peripheral firmware
|
|
env AP_PERIPH 1
|
|
|
|
FLASH_SIZE_KB 2048
|
|
|
|
# the location where the bootloader will put the firmware
|
|
# the H757 has 128k sectors, assign 2 sectors for BL
|
|
FLASH_BOOTLOADER_LOAD_KB 256
|
|
FLASH_RESERVE_START_KB 256
|
|
|
|
# crystal frequency
|
|
OSCILLATOR_HZ 24000000
|
|
|
|
# CAN1
|
|
PD0 CAN1_RX CAN1
|
|
PD1 CAN1_TX CAN1
|
|
|
|
# CAN2
|
|
#PB5 CAN2_RX CAN2
|
|
#PB6 CAN2_TX CAN2
|
|
|
|
# USB
|
|
PA11 OTG_FS_DM OTG1
|
|
PA12 OTG_FS_DP OTG1
|
|
|
|
# SERIAL
|
|
PE7 UART7_RX UART7
|
|
PE8 UART7_TX UART7
|
|
|
|
SERIAL_ORDER OTG1 UART7
|
|
|
|
# CAN Common
|
|
PG1 SLEEPCAN OUTPUT PUSHPULL SPEED_LOW LOW
|
|
PG0 SHUTDOWNCAN OUTPUT PUSHPULL SPEED_LOW LOW
|
|
|
|
# These are the pins for SWD debugging with a STlinkv2 or black-magic probe.
|
|
PA13 JTMS-SWDIO SWD
|
|
PA14 JTCK-SWCLK SWD
|
|
|
|
# override following defines as needed
|
|
define HAL_USE_ADC FALSE
|
|
STORAGE_FLASH_PAGE 14
|
|
define HAL_STORAGE_SIZE 32768
|
|
|
|
# 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
|
|
define HAL_PERIPH_ENABLE_NETWORKING
|
|
|
|
# IMU
|
|
PC10 SPI3_SCK SPI3
|
|
PC11 SPI3_MISO SPI3
|
|
PC12 SPI3_MOSI SPI3
|
|
PG15 IMU_CS CS
|
|
|
|
SPIDEV icm45686 SPI3 DEVID4 IMU_CS MODE0 24*MHZ 24*MHZ
|
|
|
|
IMU Invensensev3 SPI:icm45686 ROTATION_NONE
|
|
|
|
define HAL_PERIPH_ENABLE_IMU
|
|
|
|
# Periph GCS
|
|
define HAL_GCS_ENABLED 1
|
|
|
|
#################################
|
|
# AP_Periph - configurations specific to this App
|
|
#################################
|
|
|
|
define HAL_BARO_ALLOW_INIT_NO_BARO
|
|
|
|
define AP_NETWORKING_MAX_INSTANCES 4
|
|
|
|
define AP_SCRIPTING_ENABLED 1
|
|
define AP_FILESYSTEM_ROMFS_ENABLED 1
|
|
|
|
# listen for reboot command from uploader.py script
|
|
# undefine to disable. Use -1 to allow on all ports, otherwise serial number index defined in SERIAL_ORDER starting at 0
|
|
define HAL_PERIPH_LISTEN_FOR_SERIAL_UART_REBOOT_CMD_PORT 0
|
|
#################################
|
|
|
|
define HAL_MONITOR_THREAD_ENABLED 1
|