mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-11 10:28:29 -04:00
AP_HAL_ChibiOS: add support for H757I Evaluation board
This commit is contained in:
parent
a323807644
commit
c962292bae
85
libraries/AP_HAL_ChibiOS/hwdef/H757I_EVAL/hwdef-bl.dat
Normal file
85
libraries/AP_HAL_ChibiOS/hwdef/H757I_EVAL/hwdef-bl.dat
Normal file
@ -0,0 +1,85 @@
|
|||||||
|
# hw definition file for processing by chibios_hwdef.py
|
||||||
|
# for H743 bootloader
|
||||||
|
|
||||||
|
# MCU class and specific type
|
||||||
|
MCU STM32H7xx STM32H757xx
|
||||||
|
|
||||||
|
|
||||||
|
# USB setup
|
||||||
|
USB_STRING_MANUFACTURER "ArduPilot"
|
||||||
|
USB_STRING_PRODUCT "%BOARD%"
|
||||||
|
|
||||||
|
define CORE_CM7
|
||||||
|
define SMPS_PWR
|
||||||
|
|
||||||
|
define WATCHDOG_DISABLED
|
||||||
|
|
||||||
|
# crystal frequency
|
||||||
|
OSCILLATOR_HZ 25000000
|
||||||
|
|
||||||
|
# board ID for firmware load
|
||||||
|
APJ_BOARD_ID 146
|
||||||
|
|
||||||
|
FLASH_SIZE_KB 2048
|
||||||
|
|
||||||
|
# setup build for a peripheral firmware
|
||||||
|
env AP_PERIPH 1
|
||||||
|
|
||||||
|
EXTERNAL_PROG_FLASH_MB 128
|
||||||
|
|
||||||
|
# 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 1
|
||||||
|
|
||||||
|
PK3 LED OUTPUT LOW
|
||||||
|
PK4 LED_BOOTLOADER OUTPUT
|
||||||
|
PK5 LED_ACTIVITY OUTPUT
|
||||||
|
|
||||||
|
PB15 USART1_RX USART1
|
||||||
|
PB14 USART1_TX USART1
|
||||||
|
|
||||||
|
PA13 JTMS-SWDIO SWD
|
||||||
|
PA14 JTCK-SWCLK SWD
|
||||||
|
|
||||||
|
# the first CAN bus
|
||||||
|
# PA11 CAN1_RX CAN1
|
||||||
|
# PA12 CAN1_TX CAN1
|
||||||
|
# PC8 GPIO CAN_SLEEP OUTPUT LOW
|
||||||
|
|
||||||
|
PA11 OTG_FS_DM OTG1
|
||||||
|
PA12 OTG_FS_DP OTG1
|
||||||
|
|
||||||
|
|
||||||
|
# order of UARTs (and USB)
|
||||||
|
SERIAL_ORDER OTG1 USART1
|
||||||
|
|
||||||
|
|
||||||
|
define HAL_USE_EMPTY_STORAGE 1
|
||||||
|
define HAL_STORAGE_SIZE 16384
|
||||||
|
|
||||||
|
# reserve 256 bytes for comms between app and bootloader
|
||||||
|
RAM_RESERVE_START 256
|
||||||
|
|
||||||
|
# QSPI Flash
|
||||||
|
PF8 QUADSPI_BK1_IO0 QUADSPI1
|
||||||
|
PF9 QUADSPI_BK1_IO1 QUADSPI1
|
||||||
|
PF7 QUADSPI_BK1_IO2 QUADSPI1
|
||||||
|
PF6 QUADSPI_BK1_IO3 QUADSPI1
|
||||||
|
PG6 QUADSPI_BK1_NCS QUADSPI1
|
||||||
|
PB2 QUADSPI_CLK QUADSPI1
|
||||||
|
|
||||||
|
# IFace Device Name Bus QSPI Mode Clk Freq Size (Pow2) NCS Delay
|
||||||
|
QSPIDEV mt25q QUADSPI1 MODE1 50*MHZ 24 2
|
||||||
|
|
||||||
|
PB13 VBUS INPUT OPENDRAIN
|
||||||
|
|
||||||
|
# use DNA
|
||||||
|
define HAL_CAN_DEFAULT_NODE_ID 0
|
||||||
|
|
||||||
|
define CAN_APP_NODE_NAME "org.cubepilot.H757"
|
||||||
|
define BOOTLOADER_DEBUG SD1
|
88
libraries/AP_HAL_ChibiOS/hwdef/H757I_EVAL/hwdef.dat
Normal file
88
libraries/AP_HAL_ChibiOS/hwdef/H757I_EVAL/hwdef.dat
Normal file
@ -0,0 +1,88 @@
|
|||||||
|
# hw definition file for processing by chibios_hwdef.py
|
||||||
|
# for H757
|
||||||
|
|
||||||
|
# MCU class and specific type
|
||||||
|
MCU STM32H7xx STM32H757xx
|
||||||
|
|
||||||
|
|
||||||
|
# USB setup
|
||||||
|
USB_STRING_MANUFACTURER "ArduPilot"
|
||||||
|
USB_STRING_PRODUCT "%BOARD%"
|
||||||
|
|
||||||
|
define CORE_CM7
|
||||||
|
define SMPS_PWR
|
||||||
|
|
||||||
|
define WATCHDOG_DISABLED
|
||||||
|
|
||||||
|
# crystal frequency
|
||||||
|
OSCILLATOR_HZ 25000000
|
||||||
|
|
||||||
|
# board ID for firmware load
|
||||||
|
APJ_BOARD_ID 146
|
||||||
|
|
||||||
|
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
|
||||||
|
|
||||||
|
define HAL_LED_ON 1
|
||||||
|
|
||||||
|
PK3 LED OUTPUT LOW
|
||||||
|
PK4 LED_BOOTLOADER OUTPUT
|
||||||
|
PK5 LED_ACTIVITY OUTPUT
|
||||||
|
|
||||||
|
PB15 USART1_RX USART1
|
||||||
|
PB14 USART1_TX USART1
|
||||||
|
|
||||||
|
PA13 JTMS-SWDIO SWD
|
||||||
|
PA14 JTCK-SWCLK SWD
|
||||||
|
|
||||||
|
# the first CAN bus
|
||||||
|
# PA11 CAN1_RX CAN1
|
||||||
|
# PA12 CAN1_TX CAN1
|
||||||
|
# PC8 GPIO CAN_SLEEP OUTPUT LOW
|
||||||
|
|
||||||
|
PA11 OTG_FS_DM OTG1
|
||||||
|
PA12 OTG_FS_DP OTG1
|
||||||
|
|
||||||
|
# order of UARTs (and USB)
|
||||||
|
SERIAL_ORDER OTG1 USART1
|
||||||
|
|
||||||
|
|
||||||
|
define HAL_USE_EMPTY_STORAGE 1
|
||||||
|
define HAL_STORAGE_SIZE 16384
|
||||||
|
|
||||||
|
# reserve 256 bytes for comms between app and bootloader
|
||||||
|
RAM_RESERVE_START 256
|
||||||
|
|
||||||
|
# no ADC driver
|
||||||
|
define HAL_USE_ADC FALSE
|
||||||
|
define STM32_ADC_USE_ADC1 FALSE
|
||||||
|
define HAL_DISABLE_ADC_DRIVER TRUE
|
||||||
|
|
||||||
|
# avoid timer and RCIN threads to save memory
|
||||||
|
define HAL_NO_RCIN_THREAD
|
||||||
|
define HAL_NO_GPIO_IRQ
|
||||||
|
define NO_DATAFLASH TRUE
|
||||||
|
define DISABLE_SERIAL_ESC_COMM TRUE
|
||||||
|
|
||||||
|
# QSPI Flash
|
||||||
|
PF8 QUADSPI_BK1_IO0 QUADSPI1
|
||||||
|
PF9 QUADSPI_BK1_IO1 QUADSPI1
|
||||||
|
PF7 QUADSPI_BK1_IO2 QUADSPI1
|
||||||
|
PF6 QUADSPI_BK1_IO3 QUADSPI1
|
||||||
|
PG6 QUADSPI_BK1_NCS QUADSPI1
|
||||||
|
PB2 QUADSPI_CLK QUADSPI1
|
||||||
|
|
||||||
|
# IFace Device Name Bus QSPI Mode Clk Freq Size (Pow2) NCS Delay
|
||||||
|
QSPIDEV mt25q QUADSPI1 MODE1 50*MHZ 24 2
|
||||||
|
|
||||||
|
PB13 VBUS INPUT OPENDRAIN
|
||||||
|
|
||||||
|
# use DNA
|
||||||
|
define HAL_CAN_DEFAULT_NODE_ID 0
|
||||||
|
|
||||||
|
define CAN_APP_NODE_NAME "org.cubepilot.H757"
|
@ -19,8 +19,8 @@ mcu = {
|
|||||||
# flags of 2 means faster memory for CPU intensive work
|
# flags of 2 means faster memory for CPU intensive work
|
||||||
# flags of 4 means memory can be used for SDMMC DMA
|
# flags of 4 means memory can be used for SDMMC DMA
|
||||||
'RAM_MAP' : [
|
'RAM_MAP' : [
|
||||||
(0x20000000, 128, 2), # DTCM, tightly coupled, no DMA, fast
|
|
||||||
(0x30000000, 288, 0), # SRAM1, SRAM2, SRAM3
|
(0x30000000, 288, 0), # SRAM1, SRAM2, SRAM3
|
||||||
|
(0x20000000, 128, 2), # DTCM, tightly coupled, no DMA, fast
|
||||||
(0x38000000, 64, 1), # SRAM4. This supports both DMA and BDMA ops
|
(0x38000000, 64, 1), # SRAM4. This supports both DMA and BDMA ops
|
||||||
(0x24000000, 512, 4), # AXI SRAM. Use this for SDMMC IDMA ops
|
(0x24000000, 512, 4), # AXI SRAM. Use this for SDMMC IDMA ops
|
||||||
(0x00000400, 63, 2), # ITCM (first 1k removed, to keep address 0 unused)
|
(0x00000400, 63, 2), # ITCM (first 1k removed, to keep address 0 unused)
|
||||||
|
@ -1029,6 +1029,8 @@ def write_QSPI_table(f):
|
|||||||
bus = dev[1]
|
bus = dev[1]
|
||||||
mode = dev[2]
|
mode = dev[2]
|
||||||
speed = dev[3]
|
speed = dev[3]
|
||||||
|
size_pow2 = dev[4]
|
||||||
|
ncs_clk_delay = dev[5]
|
||||||
if not bus.startswith('QUADSPI') or bus not in qspi_list:
|
if not bus.startswith('QUADSPI') or bus not in qspi_list:
|
||||||
error("Bad QUADSPI bus in QSPIDEV line %s" % dev)
|
error("Bad QUADSPI bus in QSPIDEV line %s" % dev)
|
||||||
if mode not in ['MODE1', 'MODE3']:
|
if mode not in ['MODE1', 'MODE3']:
|
||||||
@ -1038,8 +1040,8 @@ def write_QSPI_table(f):
|
|||||||
|
|
||||||
devidx = len(devlist)
|
devidx = len(devlist)
|
||||||
f.write(
|
f.write(
|
||||||
'#define HAL_QSPI_DEVICE%-2u QSPIDesc(%-17s, %2u, QSPIDEV_%s, %7s)\n'
|
'#define HAL_QSPI_DEVICE%-2u QSPIDesc(%-17s, %2u, QSPIDEV_%s, %7s, %2u, %2u)\n'
|
||||||
% (devidx, name, qspi_list.index(bus), mode, speed))
|
% (devidx, name, qspi_list.index(bus), mode, speed, int(size_pow2), int(ncs_clk_delay)))
|
||||||
devlist.append('HAL_QSPI_DEVICE%u' % devidx)
|
devlist.append('HAL_QSPI_DEVICE%u' % devidx)
|
||||||
f.write('#define HAL_QSPI_DEVICE_LIST %s\n\n' % ','.join(devlist))
|
f.write('#define HAL_QSPI_DEVICE_LIST %s\n\n' % ','.join(devlist))
|
||||||
for dev in qspidev:
|
for dev in qspidev:
|
||||||
|
Loading…
Reference in New Issue
Block a user