mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-08 00:48:30 -04:00
246 lines
5.5 KiB
Plaintext
246 lines
5.5 KiB
Plaintext
# hw definition file for processing by chibios_hwdef.py
|
|
# for H743 bootloader
|
|
|
|
# MCU class and specific type
|
|
MCU STM32H7xx STM32H757xx
|
|
|
|
define CORE_CM7
|
|
define SMPS_PWR
|
|
|
|
# USB setup
|
|
USB_VENDOR 0x2DAE # ONLY FOR USE BY HEX! NOBODY ELSE
|
|
USB_PRODUCT 0x5001
|
|
USB_STRING_MANUFACTURER "CubePilot"
|
|
|
|
# setup build for a peripheral firmware
|
|
env AP_PERIPH 1
|
|
env AP_PERIPH_HEAVY 1
|
|
|
|
# crystal frequency
|
|
OSCILLATOR_HZ 24000000
|
|
|
|
MAIN_STACK 0x2000
|
|
|
|
# board ID for firmware load
|
|
APJ_BOARD_ID 1037
|
|
|
|
FLASH_SIZE_KB 2048
|
|
|
|
# the location where the bootloader will put the firmware
|
|
# the H743 has 128k sectors, we leave 2 sectors for BL
|
|
FLASH_BOOTLOADER_LOAD_KB 256
|
|
|
|
# board voltage
|
|
STM32_VDD 180U
|
|
|
|
# order of UARTs (and USB)
|
|
SERIAL_ORDER OTG1 EMPTY USART3 UART7
|
|
|
|
define HAL_SERIAL0_PROTOCOL SerialProtocol_None
|
|
|
|
# USART3 F9
|
|
PD9 USART3_RX USART3
|
|
PD8 USART3_TX USART3
|
|
|
|
# UART7 F9
|
|
PE7 UART7_RX UART7
|
|
PE8 UART7_TX UART7 NODMA
|
|
|
|
|
|
PC1 USB_RST OUTPUT PUSHPULL SPEED_LOW HIGH
|
|
PA7 USB_OSC_EN INPUT FLOATING
|
|
PB14 USB_CS OUTPUT PUSHPULL SPEED_LOW LOW
|
|
define STM32_USB_USE_OTG1 FALSE
|
|
define STM32_USE_USB_OTG2_HS TRUE
|
|
|
|
PA5 OTG_HS_ULPI_CK OTG_HS SPEED_HIGH
|
|
PC2 OTG_HS_ULPI_DIR OTG_HS SPEED_HIGH
|
|
#PI11 OTG_HS_ULPI_DIR OTG_HS SPEED_HIGH
|
|
PC0 OTG_HS_ULPI_STP OTG_HS SPEED_HIGH
|
|
PC3 OTG_HS_ULPI_NXT OTG_HS SPEED_HIGH
|
|
#PH4 OTG_HS_ULPI_NXT OTG_HS SPEED_HIGH
|
|
PA3 OTG_HS_ULPI_D0 OTG_HS SPEED_HIGH
|
|
PB0 OTG_HS_ULPI_D1 OTG_HS SPEED_HIGH
|
|
PB1 OTG_HS_ULPI_D2 OTG_HS SPEED_HIGH
|
|
PB10 OTG_HS_ULPI_D3 OTG_HS SPEED_HIGH
|
|
PB11 OTG_HS_ULPI_D4 OTG_HS SPEED_HIGH
|
|
PB12 OTG_HS_ULPI_D5 OTG_HS SPEED_HIGH
|
|
PB13 OTG_HS_ULPI_D6 OTG_HS SPEED_HIGH
|
|
PB5 OTG_HS_ULPI_D7 OTG_HS SPEED_HIGH
|
|
|
|
|
|
PA13 JTMS-SWDIO SWD
|
|
PA14 JTCK-SWCLK SWD
|
|
|
|
#PA13 JTMS-SWDIO INPUT
|
|
#PA14 JTCK-SWCLK INPUT
|
|
|
|
|
|
#PA13 SIG1 OUTPUT PUSHPULL SPEED_LOW HIGH
|
|
#PA14 SIG2 OUTPUT PUSHPULL SPEED_LOW HIGH
|
|
|
|
###########################
|
|
define BUILD_DEFAULT_LED_TYPE Notify_LED_NeoPixel
|
|
define NOTIFY_LED_LEN_DEFAULT 51
|
|
define CONFIGURE_PPS_PIN TRUE
|
|
define HAL_PERIPH_ENABLE_NOTIFY
|
|
define HAL_PERIPH_ENABLE_RC_OUT
|
|
|
|
FLASH_RESERVE_START_KB 256
|
|
|
|
define GPS_UBLOX_MOVING_BASELINE TRUE
|
|
define HAL_GCS_ENABLED 1
|
|
define HAL_LOGGING_ENABLED TRUE
|
|
define HAL_BOARD_LOG_DIRECTORY "/APM/LOGS"
|
|
define HAL_NO_MONITOR_THREAD
|
|
|
|
|
|
define HAL_DISABLE_LOOP_DELAY
|
|
define USB_USE_WAIT TRUE
|
|
|
|
define HAL_MINIMIZE_FEATURES 0
|
|
|
|
|
|
define HAL_DEVICE_THREAD_STACK 2048
|
|
|
|
#define AP_PARAM_MAX_EMBEDDED_PARAM 0
|
|
|
|
define HAL_BARO_ALLOW_INIT_NO_BARO
|
|
|
|
# disable dual GPS and GPS blending to save flash space
|
|
define GPS_MAX_RECEIVERS 1
|
|
define GPS_MAX_INSTANCES 1
|
|
define HAL_COMPASS_MAX_SENSORS 1
|
|
|
|
# GPS+MAG
|
|
define HAL_PERIPH_ENABLE_GPS
|
|
define HAL_PERIPH_ENABLE_MAG
|
|
define AP_INERTIALSENSOR_ENABLED 1
|
|
|
|
|
|
# enable CAN support
|
|
PA11 CAN1_RX CAN1
|
|
PA12 CAN1_TX CAN1
|
|
PC13 SLEEP_CAN1 OUTPUT PUSHPULL SPEED_LOW LOW
|
|
|
|
PB7 SWITCH_CAN2_USB OUTPUT PUSHPULL SPEED_LOW LOW
|
|
PE12 SLEEP_CAN2 OUTPUT PUSHPULL SPEED_LOW HIGH
|
|
CANFD_SUPPORTED 8
|
|
|
|
PE4 MPU_CS CS
|
|
PE2 SPI4_SCK SPI4
|
|
PE5 SPI4_MISO SPI4
|
|
PE6 SPI4_MOSI SPI4
|
|
PD12 ICM_CLK OUTPUT PUSHPULL SPEED_LOW LOW
|
|
PF0 ICM_CLK_ENABLE OUTPUT PUSHPULL SPEED_LOW LOW
|
|
SPIDEV icm42688 SPI4 DEVID4 MPU_CS MODE3 2*MHZ 8*MHZ
|
|
|
|
PB15 TIM1_CH3N TIM1 PWM(1) SPEED_HIGH OPENDRAIN
|
|
|
|
define HAL_DEFAULT_INS_FAST_SAMPLE 5
|
|
|
|
PB3 SPI1_SCK SPI1
|
|
PB4 SPI1_MISO SPI1
|
|
PD7 SPI1_MOSI SPI1
|
|
PE9 MAG_CS CS
|
|
SPIDEV rm3100 SPI1 DEVID1 MAG_CS MODE0 1*MHZ 1*MHZ
|
|
|
|
IMU Invensensev3 SPI:icm42688 ROTATION_NONE
|
|
|
|
define HAL_DEFAULT_INS_FAST_SAMPLE 5
|
|
|
|
COMPASS RM3100 SPI:rm3100 false ROTATION_PITCH_180
|
|
|
|
# Now setup the pins for the microSD card, if available.
|
|
PC8 SDMMC1_D0 SDMMC1 SPEED_HIGH
|
|
PC9 SDMMC1_D1 SDMMC1 SPEED_HIGH
|
|
PC10 SDMMC1_D2 SDMMC1 SPEED_HIGH
|
|
PC11 SDMMC1_D3 SDMMC1 SPEED_HIGH
|
|
PB8 SDMMC1_D4 SDMMC1 SPEED_HIGH
|
|
PB9 SDMMC1_D5 SDMMC1 SPEED_HIGH
|
|
PC6 SDMMC1_D6 SDMMC1 SPEED_HIGH
|
|
PC7 SDMMC1_D7 SDMMC1 SPEED_HIGH
|
|
PC12 SDMMC1_CK SDMMC1 SPEED_HIGH
|
|
PD2 SDMMC1_CMD SDMMC1 SPEED_HIGH
|
|
PC5 RESET OUTPUT PUSHPULL LOW
|
|
|
|
define HAL_SDMMC_TYPE_EMMC TRUE
|
|
|
|
define BOARD_SER1_RTSCTS_DEFAULT 0
|
|
|
|
define HAL_OS_FATFS_IO 1
|
|
define HAL_WITH_UAVCAN 1
|
|
env HAL_WITH_UAVCAN 1
|
|
define HAL_PICCOLO_CAN_ENABLE 0
|
|
define AP_UAVCAN_SLCAN_ENABLED 1
|
|
|
|
PA1 ANALOG_CAN_VOLTAGE1 ADC1 SCALE(21.404)
|
|
PA2 ANALOG_CAN_VOLTAGE2 ADC1 SCALE(21.404)
|
|
|
|
#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
|
|
PF1 GNDDET2 INPUT
|
|
PF2 GNDDET1 INPUT
|
|
#shared with SWD
|
|
|
|
#PE0 EXTERN_GPIO1 OUTPUT PUSHPULL SPEED_HIGH LOW
|
|
#PE1 EXTERN_GPIO2 OUTPUT PUSHPULL SPEED_HIGH LOW
|
|
|
|
PD6 TERM_CAN1 OUTPUT LOW GPIO(3)
|
|
PE11 TERM_CAN2 OUTPUT LOW GPIO(4)
|
|
|
|
#USB PD
|
|
#PA8 CC_DB INPUT
|
|
#PA9 CC1 INPUT
|
|
#PA10 CC2 INPUT
|
|
|
|
# This defines more ADC inputs.
|
|
PA6 ANALOG_VCC_1_8V ADC1 SCALE(2)
|
|
PA4 ANALOG_VCC_3_3V ADC1 SCALE(2)
|
|
PC4 VDD_5V_SENS ADC1 SCALE(3)
|
|
PA0 USB_VBUS_SENS ADC1 SCALE(41)
|
|
|
|
define HAL_USB_VBUS_SENS_CHAN 16
|
|
|
|
define CAN_APP_NODE_NAME "com.cubepilot.herepro"
|
|
|
|
define HAL_BOARD_TERRAIN_DIRECTORY "/APM/TERRAIN"
|
|
|
|
define COMPASS_CAL_ENABLED 1
|
|
|
|
define HAL_ENABLE_SLCAN 1
|
|
# passthrough CAN1
|
|
define HAL_DEFAULT_CPORT 1
|
|
|
|
define CONFIGURE_PPS_PIN TRUE
|
|
define AP_PERIPH_HAVE_LED TRUE
|
|
|
|
define SCRIPTING_HEAP_SIZE (64*1024)
|
|
|
|
define GPS_MOVING_BASELINE 1
|
|
|
|
define HAL_CAN_POOL_SIZE 16384
|
|
|
|
# use last 2 pages for flash storage
|
|
# H757 has 16 pages of 128k each
|
|
STORAGE_FLASH_PAGE 14
|
|
define HAL_STORAGE_SIZE 32768
|
|
|
|
define STM32_SDC_MAX_CLOCK 200000000
|
|
define HAL_PERIPH_LISTEN_FOR_SERIAL_UART_REBOOT_CMD_PORT 0
|
|
|
|
HAL_USE_USB_MSD 1
|
|
define MSD_THD_PRIO HIGHPRIO
|
|
define AP_RC_CHANNEL_ENABLED 1
|
|
#define HAL_BRD_OPTIONS_DEFAULT 8
|