ardupilot/libraries/AP_HAL_ChibiOS/hwdef/HerePro/hwdef-bl.dat

153 lines
2.7 KiB
Plaintext

# hw definition file for processing by chibios_hwdef.py
# for H743 bootloader
# MCU class and specific type
MCU STM32H7xx STM32H743xx
FULL_FEATURED_BOOTLOADER 1
# USB setup
USB_VENDOR 0x2DAE # ONLY FOR USE BY HEX! NOBODY ELSE
USB_PRODUCT 0x5011
USB_STRING_MANUFACTURER "CubePilot"
# setup build for a peripheral firmware
env AP_PERIPH 1
# crystal frequency
OSCILLATOR_HZ 24000000
# board ID for firmware load
APJ_BOARD_ID 1037
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 256
PB15 LED_2 OUTPUT LOW
PB14 LED OUTPUT LOW
# board voltage
STM32_VDD 330U
# order of UARTs (and USB)
SERIAL_ORDER OTG1 UART7
define HAL_NO_LOGGING TRUE
define HAL_NO_MONITOR_THREAD
# USART3 F9
PD9 USART3_RX USART3
PD8 USART3_TX USART3
# UART7 F9
PE7 UART7_RX UART7
PE8 UART7_TX UART7 NODMA
PA11 OTG_FS_DM OTG1
PA12 OTG_FS_DP OTG1
PA13 JTMS-SWDIO SWD
PA14 JTCK-SWCLK SWD
define USB_USE_WAIT TRUE
define HAL_USE_USB_MSD 1
define HAL_DEVICE_THREAD_STACK 2048
#define AP_PARAM_MAX_EMBEDDED_PARAM 0
define HAL_BARO_ALLOW_INIT_NO_BARO
define AP_PERIPH_HAVE_LED
define HAL_COMPASS_MAX_SENSORS 1
# GPS+MAG
define HAL_PERIPH_ENABLE_GPS
define HAL_PERIPH_ENABLE_MAG
# Add MAVLink
env FORCE_MAVLINK_INCLUDE 1
# enable CAN support
PB8 CAN1_RX CAN1
PB9 CAN1_TX CAN1
PB5 CAN2_RX CAN2
PB6 CAN2_TX CAN2
#PB5 GPIO_CAN1_SILENT OUTPUT PUSHPULL SPEED_LOW LOW
PF8 blank CS
SPIDEV profiled SPI5 DEVID1 blank MODE3 1*MHZ 1*MHZ
PE4 MPU_EXT_CS CS
PE2 SPI4_SCK SPI4
PE5 SPI4_MISO SPI4
PE6 SPI4_MOSI SPI4
PG15 spi6cs CS
PG13 SPI6_SCK SPI6
PG12 SPI6_MISO SPI6
PG14 SPI6_MOSI SPI6
PF7 SPI5_SCK SPI5
PF9 SPI5_MOSI SPI5
define BOARD_SER1_RTSCTS_DEFAULT 0
#gps f9
PD10 F91TXR INPUT
PD11 F92RST INPUT
PD13 F93SB INPUT
PD14 F94EXTINT INPUT
PD15 F95RSV1 INPUT
PG2 F97 INPUT GPIO(100)
PG3 F96RSV2 INPUT
PD4 RTKSTAT INPUT
PD5 GEOFENCESTAT INPUT
#others
PG10 can2int INPUT
PG11 can2sleep OUTPUT PUSHPULL SPEED_LOW LOW
PF1 GNDDET2 INPUT
PF2 GNDDET1 INPUT
PC6 EXTERN_GPIO1 OUTPUT GPIO(1)
PC7 EXTERN_GPIO2 OUTPUT GPIO(2)
#sensor enable
PC0 SENSEN OUTPUT HIGH
PB1 IMUINT INPUT
PB3 QCAN2TERM OUTPUT LOW GPIO(4)
PB4 QCAN2INT0 INPUT
PC13 QCAN1SLEEP OUTPUT PUSHPULL SPEED_LOW LOW
PE0 QCAN1INT INPUT
PE1 QCAN1INT0 INPUT
PE3 QCAN1INT1 INPUT
PD6 QCAN1TERM OUTPUT LOW GPIO(3)
PD7 QCAN2INT1 INPUT
PA8 QCAN12OSC1 INPUT
# This input pin is used to detect that power is valid on USB.
PA9 VBUS INPUT
PH13 VDD_33V_SENS INPUT
# This defines some input pins, currently unused.
PB2 BOOT1 INPUT
# passthrough CAN1
define HAL_DEFAULT_CPORT 1
define CAN_APP_NODE_NAME "com.cubepilot.herepro"
FULL_CHIBIOS_BOOTLOADER 1