2 changed files with 139 additions and 0 deletions
@ -0,0 +1,70 @@
@@ -0,0 +1,70 @@
|
||||
# hw definition file for processing by chibios_hwdef.py |
||||
# for H743 bootloader |
||||
|
||||
# MCU class and specific type |
||||
MCU STM32H7xx STM32H743xx |
||||
|
||||
# crystal frequency |
||||
OSCILLATOR_HZ 24000000 |
||||
|
||||
# board ID for firmware load |
||||
APJ_BOARD_ID 1400 |
||||
|
||||
FLASH_SIZE_KB 2048 |
||||
|
||||
# setup build for a peripheral firmware |
||||
env AP_PERIPH 1 |
||||
|
||||
# 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 |
||||
FLASH_BOOTLOADER_LOAD_KB 128 |
||||
|
||||
define HAL_LED_ON 0 |
||||
|
||||
# order of UARTs (and USB) |
||||
SERIAL_ORDER OTG1 UART7 |
||||
|
||||
# UART7 maps to uartF in the HAL (serial5 in SERIALn_ parameters). |
||||
PE7 UART7_RX UART7 |
||||
PE8 UART7_TX UART7 |
||||
|
||||
# Pin for PWM Voltage Selection |
||||
PB4 PWM_VOLT_SEL OUTPUT HIGH |
||||
|
||||
PA11 OTG_FS_DM OTG1 |
||||
PA12 OTG_FS_DP OTG1 |
||||
|
||||
PA13 JTMS-SWDIO SWD |
||||
PA14 JTCK-SWCLK SWD |
||||
|
||||
define HAL_USE_EMPTY_STORAGE 1 |
||||
define HAL_STORAGE_SIZE 16384 |
||||
|
||||
# Add CS pins to ensure they are high in bootloader |
||||
PC1 MAG_CS CS |
||||
PC2 MPU_CS CS |
||||
PC13 GYRO_EXT_CS CS |
||||
PC14 BARO_EXT_CS CS |
||||
PC15 ACCEL_EXT_CS CS |
||||
PD7 BARO_CS CS |
||||
PE4 MPU_EXT_CS CS |
||||
PD10 FRAM_CS CS SPEED_VERYLOW |
||||
|
||||
# the first CAN bus |
||||
PD0 CAN1_RX CAN1 |
||||
PD1 CAN1_TX CAN1 |
||||
|
||||
# This defines the pins for the 2nd CAN interface, if available. |
||||
PB6 CAN2_TX CAN2 |
||||
PB12 CAN2_RX CAN2 |
||||
|
||||
# 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 "org.ardupilot.CubeOrange-periph" |
@ -0,0 +1,69 @@
@@ -0,0 +1,69 @@
|
||||
include ../CubeOrange/hwdef.dat |
||||
|
||||
undef COMPASS |
||||
undef IOMCU_UART |
||||
undef USART6 |
||||
undef ROMFS |
||||
undef HAL_HAVE_SAFETY_SWITCH |
||||
undef IMU |
||||
undef HAL_CHIBIOS_ARCH_FMUV3 |
||||
# board ID for firmware load |
||||
APJ_BOARD_ID 1400 |
||||
|
||||
# setup build for a peripheral firmware |
||||
env AP_PERIPH 1 |
||||
|
||||
define PERIPH_FW TRUE |
||||
|
||||
define HAL_BUILD_AP_PERIPH |
||||
|
||||
define HAL_PERIPH_ENABLE_GPS |
||||
define HAL_PERIPH_ENABLE_MAG |
||||
define HAL_PERIPH_ENABLE_BARO |
||||
|
||||
# use the app descriptor needed by MissionPlanner for CAN upload |
||||
env APP_DESCRIPTOR MissionPlanner |
||||
|
||||
# single GPS and compass for peripherals |
||||
define GPS_MAX_RECEIVERS 1 |
||||
define GPS_MAX_INSTANCES 1 |
||||
define HAL_COMPASS_MAX_SENSORS 1 |
||||
|
||||
define HAL_NO_GCS |
||||
define HAL_NO_LOGGING |
||||
define HAL_NO_MONITOR_THREAD |
||||
|
||||
define HAL_DISABLE_LOOP_DELAY |
||||
|
||||
define HAL_USE_RTC FALSE |
||||
define DISABLE_SERIAL_ESC_COMM TRUE |
||||
define NO_DATAFLASH TRUE |
||||
|
||||
define HAL_NO_RCIN_THREAD |
||||
|
||||
define HAL_BARO_ALLOW_INIT_NO_BARO |
||||
|
||||
define HAL_USE_ADC FALSE |
||||
define STM32_ADC_USE_ADC1 FALSE |
||||
define HAL_DISABLE_ADC_DRIVER TRUE |
||||
|
||||
define HAL_CAN_DEFAULT_NODE_ID 0 |
||||
|
||||
define CAN_APP_NODE_NAME "org.ardupilot.CubeOrange-periph" |
||||
|
||||
# reserve 256 bytes for comms between app and bootloader |
||||
RAM_RESERVE_START 256 |
||||
|
||||
env DISABLE_SCRIPTING 1 |
||||
|
||||
# use blue LED |
||||
define HAL_GPIO_PIN_LED HAL_GPIO_PIN_FMU_LED_AMBER |
||||
|
||||
undef HAL_OS_FATFS_IO |
||||
|
||||
undef SDMMC1 |
||||
|
||||
MAIN_STACK 0x2000 |
||||
PROCESS_STACK 0x6000 |
||||
|
||||
define HAL_CAN_DRIVER_DEFAULT 1 |
Loading…
Reference in new issue