MCU STM32H7xx STM32H743xx # USB setup USB_VENDOR 0x2DAE # ONLY FOR USE BY HEX! NOBODY ELSE USB_PRODUCT 0x1016 USB_STRING_MANUFACTURER "epesign" OSCILLATOR_HZ 0 FLASH_SIZE_KB 2048 FLASH_RESERVE_START_KB 0 APJ_BOARD_ID 9 STM32_ST_USE_TIMER 5 # order of I2C buses I2C_ORDER I2C1 SERIAL_ORDER OTG1 USART2 UART7 UART8 PD13 TIM4_CH2 TIM4 RCININT PULLDOWN define HAL_SERIAL2_PROTOCOL SerialProtocol_RCIN # This is the pin to enable the sensors rail. It can be used to power # cycle sensors to recover them in case there are problems with power on # timing affecting sensor stability. We pull it LOW on startup, which # means sensors off, then it is pulled HIGH in peripheral_power_enable() PE3 VDD_3V3_SENSORS_EN OUTPUT LOW # Now the VDD sense pin. This is used to sense primary board voltage. PA4 VDD_5V_SENS ADC1 SCALE(2) # These are the pins for SWD debugging with a STlinkv2 or black-magic probe. PA13 JTMS-SWDIO SWD PA14 JTCK-SWCLK SWD # This defines the pins for the 2nd CAN interface, if available. PB6 CAN2_TX CAN2 PB12 CAN2_RX CAN2 # the first CAN bus PD0 CAN1_RX CAN1 PD1 CAN1_TX CAN1 PE0 UART8_RX UART8 PE1 UART8_TX UART8 PD5 USART2_TX USART2 PD6 USART2_RX USART2 # Now we define the pins that USB is connected on. PA11 OTG_FS_DM OTG1 PA12 OTG_FS_DP OTG1 # compass as part of ICM20948 on newer cubes COMPASS AK09916:probe_ICM20948 0 ROTATION_ROLL_180_YAW_90 # 2nd compass is part of the 2nd invensense IMU ICM20649 COMPASS AK8963:probe_mpu9250 1 ROTATION_YAW_270 #COMPASS HMC5843 I2C:0:0x1E false ROTATION_YAW_270 # Enable all IMUs to be used and therefore three active EKF Lanes define HAL_EKF_IMU_MASK_DEFAULT 7 # This is the invensense data-ready pin. We don't use it in the # default driver. PD15 MPU_DRDY INPUT # More CS pins for more sensors. The labels for all CS pins need to # match the SPI device table later in this file. PC13 GYRO_EXT_CS CS PC15 MAG_EXT_CS CS PD7 BARO_CS CS # The CS pin for FRAM (ramtron). This one is marked as using # SPEED_VERYLOW, which matches the HAL_PX4 setup. PD10 FRAM_CS CS SPEED_VERYLOW # the 2nd SPI bus PB13 SPI2_SCK SPI2 PB14 SPI2_MISO SPI2 PB15 SPI2_MOSI SPI2 # the 1nd I2C bus PB10 I2C2_SCL I2C1 PB11 I2C2_SDA I2C1 # UART7 maps to SERIAL5. PE7 UART7_RX UART7 PE8 UART7_TX UART7 # This defines the CS pin for the magnetometer and first IMU. Note # that CS pins are software controlled, and are not tied to a particular # SPI bus. #IMU0 - ICM20649 PC2 MPU_CS CS PA5 SPI1_SCK SPI1 PA6 SPI1_MISO SPI1 PA7 SPI1_MOSI SPI1 # Now setup SPI bus4. PE2 SPI4_SCK SPI4 PE5 SPI4_MISO SPI4 PE6 SPI4_MOSI SPI4 PE4 MPU_EXT_CS CS #LIS3MDLTR MODE3 500*KHZ 500*KHZ SPIDEV ms5611 SPI1 DEVID3 BARO_CS MODE3 2*MHZ 8*MHZ SPIDEV icm20649 SPI1 DEVID4 MPU_CS MODE3 2*MHZ 8*MHZ SPIDEV icm20948 SPI4 DEVID5 MPU_EXT_CS MODE3 4*MHZ 8*MHZ SPIDEV lis3mdl SPI4 DEVID6 MAG_EXT_CS MODE3 4*MHZ 8*MHZ SPIDEV ramtron SPI2 DEVID10 FRAM_CS MODE3 8*MHZ 8*MHZ # Now setup the pins for the microSD card, if available. # pins for SD card: PC8 SDMMC1_D0 SDMMC1 PC9 SDMMC1_D1 SDMMC1 PC10 SDMMC1_D2 SDMMC1 PC11 SDMMC1_D3 SDMMC1 PC12 SDMMC1_CK SDMMC1 PD2 SDMMC1_CMD SDMMC1 define HAL_OS_FATFS_IO 1 define HAL_BOARD_LOG_DIRECTORY "/APM/LOGS" define HAL_BOARD_TERRAIN_DIRECTORY "/APM/TERRAIN" IMU Invensensev2 SPI:icm20649 ROTATION_NONE IMU Invensensev2 SPI:icm20948 ROTATION_NONE BARO MS56XX SPI:ms5611 COMPASS LIS3MDL I2C:0:0x1e false ROTATION_YAW_270 COMPASS LIS3MDL SPI:lis3mdl false ROTATION_YAW_270 #CHECK_ICM20948 spi_check_register_inv2("icm20948", INV2REG_WHOAMI, INV2_WHOAMI_ICM20948) #CHECK_IMU0_PRESENT $CHECK_ICM20948 #BOARD_VALIDATE $CHECK_IMU0_PRESENT PC14 HEATER_EN OUTPUT LOW GPIO(80) define HAL_HEATER_GPIO_PIN 80 # Setup the IMU heater define HAL_HAVE_IMU_HEATER 1 define HAL_IMU_TEMP_DEFAULT 45 define HAL_IMUHEAT_P_DEFAULT 50 define HAL_IMUHEAT_I_DEFAULT 0.07 define HAL_IMU_TEMP_MARGIN_LOW_DEFAULT 5 PE9 SBUS_INVERT OUTPUT LOW PUSHPULL GPIO(0) PE12 LED1 OUTPUT LOW PUSHPULL GPIO(1) PB0 LED2 OUTPUT LOW PUSHPULL GPIO(2) PB1 LED2 OUTPUT LOW PUSHPULL GPIO(3) #define HAL_USE_EMPTY_STORAGE TRUE define HAL_USE_ADC FALSE define HAL_BARO_ALLOW_INIT_NO_BARO define ALLOW_ARM_NO_COMPASS define HAL_PROBE_EXTERNAL_I2C_COMPASSES define HAL_I2C_INTERNAL_MASK 0 define HAL_COMPASS_AUTO_ROT_DEFAULT 2 # Now we start defining some PWM pins. We also map these pins to GPIO # values, so users can set BRD_PWM_COUNT to choose how many of the PWM # outputs on the primary MCU are setup as PWM and how many as # GPIOs. To match HAL_PX4 we number the GPIOs for the PWM outputs # starting at 50. PA0 TIM2_CH1 TIM2 PWM(1) GPIO(50) PA1 TIM2_CH2 TIM2 PWM(2) GPIO(51) PA2 TIM2_CH3 TIM2 PWM(3) GPIO(52) PA3 TIM2_CH4 TIM2 PWM(4) GPIO(53) define HAL_STORAGE_SIZE 16384 define HAL_WITH_RAMTRON 1