2024-01-24 22:45:15 -04:00
|
|
|
# hw definition file for processing by chibios_hwdef.py
|
|
|
|
# for the BotBloxSwitch hardware
|
|
|
|
|
|
|
|
# default to all pins low to avoid ESD issues
|
|
|
|
DEFAULTGPIO OUTPUT LOW PULLDOWN
|
|
|
|
|
|
|
|
# MCU class and specific type
|
|
|
|
MCU STM32H7xx STM32H723xx
|
|
|
|
|
|
|
|
# crystal frequency
|
2024-07-10 03:41:05 -03:00
|
|
|
OSCILLATOR_HZ 16000000
|
2024-01-24 22:45:15 -04:00
|
|
|
|
|
|
|
# setup build for a peripheral bootloader
|
|
|
|
env AP_PERIPH 1
|
|
|
|
|
|
|
|
# board ID for firmware load
|
|
|
|
APJ_BOARD_ID AP_HW_BotBloxSwitch
|
|
|
|
|
|
|
|
FLASH_RESERVE_START_KB 128
|
|
|
|
|
|
|
|
define HAL_STORAGE_SIZE 32768
|
|
|
|
|
|
|
|
# use last 2 pages for flash storage
|
|
|
|
# H723 has 8 pages of 128k each
|
|
|
|
STORAGE_FLASH_PAGE 6
|
|
|
|
|
|
|
|
# flash size
|
|
|
|
FLASH_SIZE_KB 1024
|
|
|
|
|
|
|
|
env OPTIMIZE -Os
|
|
|
|
|
|
|
|
# pins for SWD debugging
|
|
|
|
PA13 JTMS-SWDIO SWD
|
|
|
|
PA14 JTCK-SWCLK SWD
|
|
|
|
|
|
|
|
# USB
|
|
|
|
PA11 OTG_HS_DM OTG1
|
|
|
|
PA12 OTG_HS_DP OTG1
|
|
|
|
PA9 VBUS INPUT OPENDRAIN
|
|
|
|
|
|
|
|
# CAN bus
|
|
|
|
PD0 CAN1_RX CAN1
|
|
|
|
PD1 CAN1_TX CAN1
|
|
|
|
|
2024-07-10 03:41:05 -03:00
|
|
|
#PD4 USART2_DE USART2
|
|
|
|
PD5 USART2_TX USART2
|
|
|
|
PD6 USART2_RX USART2
|
|
|
|
|
2024-01-24 22:45:15 -04:00
|
|
|
PD8 USART3_TX USART3
|
|
|
|
PD9 USART3_RX USART3
|
|
|
|
PD12 USART3_RTS USART3
|
|
|
|
PD11 USART3_CTS USART3
|
|
|
|
|
|
|
|
# LEDs
|
2024-07-10 03:41:05 -03:00
|
|
|
PC0 LED_STT1 OUTPUT OPENDRAIN HIGH
|
|
|
|
PA4 LED_STT2 OUTPUT OPENDRAIN HIGH
|
2024-01-24 22:45:15 -04:00
|
|
|
define HAL_LED_ON 0
|
|
|
|
|
2024-07-10 03:41:05 -03:00
|
|
|
# use first LED
|
|
|
|
define HAL_GPIO_PIN_LED HAL_GPIO_PIN_LED_STT1
|
|
|
|
|
|
|
|
# Ethernet switch chip reset pin
|
|
|
|
PD13 GPIO_ETH_RST OUTPUT HIGH PULLUP
|
|
|
|
# CAN1 standby GPIO
|
|
|
|
PA0 GPIO_CAN_S OUTPUT LOW PULLUP
|
|
|
|
|
|
|
|
# GPIO/PWMs
|
|
|
|
#PC6 TIM3_CH1 TIM3 PWM(1) GPIO(100)
|
|
|
|
#PB14 TIM12_CH1 TIM12 PWM(2) GPIO(101)
|
|
|
|
#PB15 TIM12_CH2 TIM12 PWM(3) GPIO(102)
|
2024-01-24 22:45:15 -04:00
|
|
|
|
|
|
|
PC1 ETH_MDC ETH1
|
|
|
|
PA2 ETH_MDIO ETH1
|
|
|
|
PC4 ETH_RMII_RXD0 ETH1
|
|
|
|
PC5 ETH_RMII_RXD1 ETH1
|
2024-07-10 03:41:05 -03:00
|
|
|
PB12 ETH_RMII_TXD0 ETH1
|
2024-01-24 22:45:15 -04:00
|
|
|
PB13 ETH_RMII_TXD1 ETH1
|
2024-07-10 03:41:05 -03:00
|
|
|
PB11 ETH_RMII_TX_EN ETH1
|
2024-01-24 22:45:15 -04:00
|
|
|
PA7 ETH_RMII_CRS_DV ETH1
|
|
|
|
PA1 ETH_RMII_REF_CLK ETH1
|
|
|
|
|
2024-06-27 14:00:22 -03:00
|
|
|
define BOARD_PHY_ADDRESS 5
|
2024-01-24 22:45:15 -04:00
|
|
|
define BOARD_PHY_RMII
|
|
|
|
|
2024-06-27 14:00:22 -03:00
|
|
|
# auto-negotiation doesn't work, force 100MBit full duplex
|
|
|
|
define STM32_MAC_PHY_LINK_TYPE MAC_LINK_100_FULLDUPLEX
|
|
|
|
|
2024-07-10 03:41:05 -03:00
|
|
|
define HAL_PERIPH_ENABLE_NETWORKING
|
|
|
|
define AP_NETWORKING_MAX_INSTANCES 4
|
2024-01-24 22:45:15 -04:00
|
|
|
|
|
|
|
# allow load from USB
|
|
|
|
SERIAL_ORDER OTG1 USART3
|
|
|
|
|
2024-07-10 03:41:05 -03:00
|
|
|
define HAL_RCIN_THREAD_ENABLED 1
|
|
|
|
define HAL_SCHEDULER_LOOP_DELAY_ENABLED 1
|
|
|
|
|
2024-01-24 22:45:15 -04:00
|
|
|
define HAL_USE_ADC FALSE
|
|
|
|
|
2024-07-10 03:41:05 -03:00
|
|
|
define AP_SERIALMANAGER_REGISTER_ENABLED 1
|
|
|
|
define AP_SCRIPTING_ENABLED 1
|
|
|
|
define AP_FILESYSTEM_ROMFS_ENABLED 1
|
2024-01-24 22:45:15 -04:00
|
|
|
|
2024-06-27 14:00:22 -03:00
|
|
|
# keep ROMFS uncompressed as we don't have enough RAM
|
|
|
|
# to uncompress the network enabled bootloader at runtime
|
|
|
|
env ROMFS_UNCOMPRESSED True
|
|
|
|
|
2024-07-10 03:41:05 -03:00
|
|
|
include ../include/network_PPPGW.inc
|
2024-04-03 06:01:28 -03:00
|
|
|
|
|
|
|
define HAL_MONITOR_THREAD_ENABLED 1
|