# 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 env OPTIMIZE -Os # crystal frequency OSCILLATOR_HZ 24000000 # board ID for firmware load APJ_BOARD_ID 1070 FLASH_SIZE_KB 2048 # bootloader is installed at zero offset FLASH_RESERVE_START_KB 128 # the location where the bootloader will put the firmware # the H743 has 128k sectors FLASH_BOOTLOADER_LOAD_KB 128 define HAL_LED_ON 0 # supports upto 8MBits/s CANFD_SUPPORTED 8 # use last 2 pages for flash storage # H757 has 16 pages of 128k each STORAGE_FLASH_PAGE 14 define HAL_STORAGE_SIZE 32768 # ADC setup PF11 FMU_SERVORAIL_VCC_SENS ADC1 PA6 RSSI_IN ADC1 SCALE(2) # CAN config PB14 GPIOCAN2_TERM OUTPUT HIGH PC12 GPIOCAN1_SHUTDOWN OUTPUT LOW PF1 GPIOCAN2_SHUTDOWN OUTPUT LOW PA12 CAN1_TX CAN1 PB8 CAN1_RX CAN1 PB6 CAN2_TX CAN2 PB5 CAN2_RX CAN2 # SPI2 PB12 ICM_CS CS PC1 SPI2_MOSI SPI2 PC2 SPI2_MISO SPI2 PB13 SPI2_SCK SPI2 # SPI4 PE4 BARO_CS CS PE6 SPI4_MOSI SPI4 PE5 SPI4_MISO SPI4 PE2 SPI4_SCK SPI4 # Sensors SPIDEV icm42688 SPI2 DEVID1 ICM_CS MODE3 2*MHZ 8*MHZ SPIDEV ms5611 SPI4 DEVID2 BARO_CS MODE3 20*MHZ 20*MHZ BARO MS56XX SPI:ms5611 IMU Invensensev3 SPI:icm42688 ROTATION_YAW_180 CHECK_ICM42688 spi_check_register("icm42688", INV3REG_WHOAMI, INV3_WHOAMI_ICM42688) CHECK_ICM45686 spi_check_register("icm42688", INV3REG_456_WHOAMI, INV3_WHOAMI_ICM45686) CHECK_MS5611 check_ms5611("ms5611") CHECK_IMU0_PRESENT $CHECK_ICM42688 || $CHECK_ICM45686 CHECK_BARO0_PRESENT $CHECK_MS5611 BOARD_VALIDATE $CHECK_IMU0_PRESENT $CHECK_BARO0_PRESENT define HAL_CHIBIOS_ARCH_FMUV3 1 define BOARD_TYPE_DEFAULT 3 # RCIN PC8 TIM8_CH3 TIM8 RCININT PULLDOWN # SWD PA13 JTMS-SWDIO SWD PA14 JTCK-SWCLK SWD # GPIO PD10 FMU_LED_AMBER OUTPUT HIGH OPENDRAIN GPIO(0) PE15 VDD_BRICK_nVALID INPUT PULLUP PG0 VDD_BRICK2_nVALID INPUT PULLUP PG5 VDD_SERVO_FAULT INPUT PULLUP PG1 PWM_VOLT_SEL OUTPUT HIGH GPIO(3) # Control of Spektrum power pin PB2 SPEKTRUM_PWR OUTPUT HIGH GPIO(73) define HAL_GPIO_SPEKTRUM_PWR 73 # Spektrum Power is Active High define HAL_SPEKTRUM_PWR_ENABLED 1 # Timer PA8 TIM1_CH1 TIM1 PWM(1) GPIO(50) BIDIR PA9 TIM1_CH2 TIM1 PWM(2) GPIO(51) PA10 TIM1_CH3 TIM1 PWM(3) GPIO(52) BIDIR PA11 TIM1_CH4 TIM1 PWM(4) GPIO(53) PA5 TIM2_CH1 TIM2 PWM(5) GPIO(54) BIDIR PA1 TIM2_CH2 TIM2 PWM(6) GPIO(55) PB10 TIM2_CH3 TIM2 PWM(7) GPIO(56) BIDIR PB11 TIM2_CH4 TIM2 PWM(8) GPIO(57) # Correctly set Direction of PWMs # if UNIDIR is set then BIDIR must be reset PB0 BIDIR_ENABLED OUTPUT LOW GPIO(4) PA7 HP_UNIDIR_ENABLED OUTPUT HIGH GPIO(5) # UART connected to FMU, uses DMA PE7 UART7_RX UART7 SPEED_VERYLOW LOW_NOISE PE8 UART7_TX UART7 SPEED_VERYLOW # UART for SBUS out PC7 USART6_RX USART6 SPEED_HIGH LOW PC6 USART6_TX USART6 # UART for DSM input # TX side is for IO debug, and is unused PC10 USART3_TX USART3 SPEED_HIGH PC11 USART3_RX USART3 SPEED_HIGH # UART for debug PE1 UART8_TX UART8 PE0 UART8_RX UART8 # UART for RCIN PD1 UART4_TX UART4 # USART for future use PD5 USART2_TX USART2 SPEED_HIGH PD6 USART2_RX USART2 SPEED_HIGH PD4 USART2_RTS USART2 SPEED_HIGH PD3 USART2_CTS USART2 SPEED_HIGH # order of UARTs SERIAL_ORDER UART8 UART7 USART3 USART6 UART4 USART2 # use 2 MBaud when talking to primary controller define DEFAULT_SERIAL1_BAUD 8000000 define DEFAULT_SERIAL1_PROTOCOL SerialProtocol_PPP define DEFAULT_SERIAL3_PROTOCOL SerialProtocol_Sbus1 define DEFAULT_SERIAL4_PROTOCOL SerialProtocol_RCIN define AP_NETWORKING_BACKEND_PPP 1 # only use pulse input for PPM, other protocols # are on serial define HAL_RCIN_PULSE_PPM_ONLY define MAV_SYSTEM_ID 3