You can not select more than 25 topics
Topics must start with a letter or number, can include dashes ('-') and can be up to 35 characters long.
220 lines
4.4 KiB
220 lines
4.4 KiB
# hw definition file for processing by chibios_hwdef.py |
|
# for H743 bootloader |
|
|
|
# MCU class and specific type |
|
MCU STM32H7xx STM32H743xx |
|
|
|
# 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 |
|
|
|
# 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, we leave 2 sectors for BL |
|
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 OTG2 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 |
|
|
|
|
|
PA11 OTG_FS_DM OTG1 |
|
PA12 OTG_FS_DP OTG1 |
|
|
|
PA13 JTMS-SWDIO SWD |
|
PA14 JTCK-SWCLK SWD |
|
|
|
########################### |
|
define BUILD_DEFAULT_LED_TYPE Notify_LED_ProfiLED_SPI |
|
define NOTIFY_LED_LEN_DEFAULT 16 |
|
define CONFIGURE_PPS_PIN TRUE |
|
|
|
FLASH_RESERVE_START_KB 256 |
|
|
|
define GPS_UBLOX_MOVING_BASELINE TRUE |
|
define HAL_NO_LOGGING TRUE |
|
define HAL_NO_MONITOR_THREAD |
|
|
|
define PERIPH_FW TRUE |
|
|
|
define HAL_DISABLE_LOOP_DELAY |
|
define USB_USE_WAIT TRUE |
|
define HAL_USE_USB_MSD TRUE |
|
|
|
define HAL_MINIMIZE_FEATURES 0 |
|
|
|
define HAL_BUILD_AP_PERIPH |
|
|
|
define HAL_DEVICE_THREAD_STACK 2048 |
|
|
|
#define AP_PARAM_MAX_EMBEDDED_PARAM 0 |
|
|
|
define HAL_BARO_ALLOW_INIT_NO_BARO |
|
|
|
define HAL_STORAGE_SIZE 16384 |
|
|
|
# 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 HAL_INS_ENABLED 1 |
|
|
|
# use the app descriptor needed by MissionPlanner for CAN upload |
|
env APP_DESCRIPTOR MissionPlanner |
|
|
|
# enable CAN support |
|
PB8 CAN1_RX CAN1 |
|
PB9 CAN1_TX CAN1 |
|
PB5 CAN2_RX CAN2 |
|
PB6 CAN2_TX CAN2 |
|
|
|
PA4 MPU_CS CS |
|
PA5 SPI1_SCK SPI1 |
|
PA6 SPI1_MISO SPI1 |
|
PA7 SPI1_MOSI SPI1 |
|
SPIDEV icm20948 SPI1 DEVID4 MPU_CS MODE3 4*MHZ 8*MHZ |
|
|
|
PF8 blank CS |
|
SPIDEV profiled SPI5 DEVID1 blank MODE3 1*MHZ 1*MHZ |
|
|
|
IMU Invensensev2 SPI:icm20948 ROTATION_YAW_270 |
|
|
|
define HAL_DEFAULT_INS_FAST_SAMPLE 5 |
|
|
|
# compass as part of ICM20948 on newer cubes |
|
COMPASS AK09916:probe_ICM20948 0 ROTATION_ROLL_180_YAW_90 |
|
|
|
# one baro |
|
#BARO MS56XX I2C:0:0x77 |
|
|
|
PE4 CSPI4_CS CS |
|
PE2 SPI4_SCK SPI4 |
|
PE5 SPI4_MISO SPI4 |
|
PE6 SPI4_MOSI SPI4 |
|
|
|
|
|
PG15 CSPI6_CS CS |
|
PG13 SPI6_SCK SPI6 |
|
PG12 SPI6_MISO SPI6 |
|
PG14 SPI6_MOSI SPI6 |
|
|
|
PF7 SPI5_SCK SPI5 |
|
PF9 SPI5_MOSI SPI5 |
|
|
|
# Now setup the pins for the microSD card, if available. |
|
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 BOARD_PWM_COUNT_DEFAULT 0 |
|
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 |
|
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 defines more ADC inputs. |
|
PC3 ANALOG_VCC_1_8V ADC1 SCALE(2) |
|
PC4 ANALOG_VCC_5V_PIN ADC1 SCALE(2.044) |
|
|
|
# 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 |
|
|
|
# reserve 256 bytes for comms between app and bootloader |
|
RAM_RESERVE_START 256 |
|
|
|
# use DNA |
|
define HAL_CAN_DEFAULT_NODE_ID 0 |
|
|
|
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)
|
|
|