mirror of https://github.com/ArduPilot/ardupilot
140 lines
2.8 KiB
Plaintext
140 lines
2.8 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
|
|
|
|
# setup build for a peripheral firmware
|
|
env AP_PERIPH 1
|
|
|
|
FLASH_SIZE_KB 2048
|
|
APJ_BOARD_ID 1043
|
|
|
|
|
|
# the location where the bootloader will put the firmware
|
|
# the H757 has 128k sectors
|
|
FLASH_BOOTLOADER_LOAD_KB 256
|
|
FLASH_RESERVE_START_KB 256
|
|
|
|
# use last 2 pages for flash storage
|
|
# H757 has 16 pages of 128k each
|
|
STORAGE_FLASH_PAGE 14
|
|
define HAL_STORAGE_SIZE 32768
|
|
|
|
# reserve space for flash storage in last 2 sectors
|
|
FLASH_RESERVE_END_KB 256
|
|
|
|
# crystal frequency
|
|
OSCILLATOR_HZ 24000000
|
|
|
|
CANFD_SUPPORTED 8
|
|
|
|
STDOUT_SERIAL SD6
|
|
STDOUT_BAUDRATE 57600
|
|
|
|
PC6 USART6_TX USART6
|
|
|
|
PB6 USART1_TX USART1 GPIO(7)
|
|
PB7 USART1_RX USART1 GPIO(8)
|
|
|
|
# GPS
|
|
PD5 USART2_TX USART2 GPIO(9)
|
|
PD6 USART2_RX USART2 GPIO(10)
|
|
|
|
PA11 UART4_RX UART4
|
|
PA12 UART4_TX UART4
|
|
|
|
define GPIO_USART1_TX 7
|
|
define GPIO_USART1_RX 8
|
|
define GPIO_USART2_TX 9
|
|
define GPIO_USART2_RX 10
|
|
|
|
# CubeID when present
|
|
PE0 UART8_RX UART8
|
|
PE1 UART8_TX UART8
|
|
|
|
SERIAL_ORDER USART1 UART4 UART8 USART2
|
|
|
|
define DRONEID_MODULE_CHAN MAVLINK_COMM_2
|
|
|
|
PA13 JTMS-SWDIO SWD
|
|
PA14 JTCK-SWCLK SWD
|
|
|
|
define HAL_LED_ON 0
|
|
|
|
# enable CAN support
|
|
PD0 CAN1_RX CAN1
|
|
PD1 CAN1_TX CAN1
|
|
PD2 SLEEPCAN1 OUTPUT PUSHPULL SPEED_LOW LOW
|
|
PD3 TERMCAN1 OUTPUT HIGH GPIO(3)
|
|
|
|
PE7 UART7_RX UART7
|
|
PE8 UART7_TX UART7
|
|
|
|
# single CAN for now
|
|
#PB12 CAN2_RX CAN2
|
|
#PB13 CAN2_TX CAN2
|
|
#PB10 SLEEPCAN2 OUTPUT PUSHPULL SPEED_LOW HIGH
|
|
#PB11 TERMCAN2 OUTPUT HIGH GPIO(4)
|
|
|
|
PB3 SPI3_SCK SPI3
|
|
PB4 SPI3_MISO SPI3
|
|
PB2 SPI3_MOSI SPI3
|
|
PB1 MAG_CS CS
|
|
|
|
# analog input
|
|
define HAL_USE_ADC FALSE
|
|
define STM32_ADC_USE_ADC1 FALSE
|
|
define HAL_DISABLE_ADC_DRIVER TRUE
|
|
|
|
define HAL_PERIPH_ENABLE_BARO TRUE
|
|
|
|
SPIDEV rm3100 SPI3 DEVID1 MAG_CS MODE0 1*MHZ 1*MHZ
|
|
COMPASS RM3100 SPI:rm3100 false ROTATION_YAW_180
|
|
define AP_RM3100_REVERSAL_MASK 4
|
|
|
|
PA8 ICM_CS CS
|
|
PA9 BARO_CS CS
|
|
PA5 SPI1_SCK SPI1
|
|
PA6 SPI1_MISO SPI1
|
|
PA7 SPI1_MOSI SPI1
|
|
SPIDEV icm42688 SPI1 DEVID4 ICM_CS MODE3 2*MHZ 8*MHZ
|
|
SPIDEV ms5611 SPI1 DEVID3 BARO_CS MODE3 20*MHZ 20*MHZ
|
|
|
|
BARO MS56XX SPI:ms5611
|
|
|
|
# WS2812 LED
|
|
PB8 TIM4_CH3 TIM4 PWM(1)
|
|
PB9 TIM4_CH4 TIM4 PWM(2)
|
|
|
|
define GPS_MAX_RECEIVERS 1
|
|
define GPS_MAX_INSTANCES 1
|
|
define HAL_COMPASS_MAX_SENSORS 1
|
|
|
|
|
|
define HAL_PERIPH_ENABLE_GPS 1
|
|
define HAL_PERIPH_ENABLE_MAG 1
|
|
define GPS_MOVING_BASELINE 1
|
|
define HAL_PERIPH_GPS_PORT_DEFAULT 3
|
|
|
|
#PD11 GPS_TP1 OUTPUT HIGH GPIO(5)
|
|
#PD7 GPS_PPS INPUT FLOATING GPIO(6)
|
|
#define CONFIGURE_PPS_PIN TRUE
|
|
#define HAL_GPIO_PPS 6
|
|
|
|
# GPS enable pin
|
|
# PD13 GPS_ENABLE OUTPUT HIGH GPIO(20)
|
|
|
|
# for ProfiLed we need RC out and notify
|
|
define HAL_PERIPH_ENABLE_RC_OUT
|
|
define HAL_PERIPH_ENABLE_NOTIFY
|
|
define AP_SERIALLED_ENABLED 1
|
|
|
|
define HAL_SERIAL_ESC_COMM_ENABLED 1
|
|
define HAL_RCIN_THREAD_ENABLED 1
|
|
define HAL_SCHEDULER_LOOP_DELAY_ENABLED 1
|
|
define HAL_MONITOR_THREAD_ENABLED 1
|