mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-02-26 09:43:57 -04:00
HAL_ChibiOS: setup more bootloader config files
This commit is contained in:
parent
6771a3d65a
commit
3fc6824bfb
@ -34,6 +34,9 @@ void *malloc_ccm(size_t size);
|
||||
void *malloc_dtcm(size_t size);
|
||||
void *malloc_dma(size_t size);
|
||||
|
||||
// flush all dcache
|
||||
void memory_flush_all(void);
|
||||
|
||||
// UTC system clock handling
|
||||
void stm32_set_utc_usec(uint64_t time_utc_usec);
|
||||
uint64_t stm32_get_utc_usec(void);
|
||||
|
@ -440,8 +440,8 @@ define HAL_I2C_MAX_CLOCK 100000
|
||||
DMA_NOSHARE USART6_TX USART6_RX ADC1
|
||||
DMA_PRIORITY USART6*
|
||||
|
||||
# run without a bootloader for now, use DFU upload
|
||||
FLASH_RESERVE_START_KB 0
|
||||
# start on 2nd sector (1st sector for bootloader)
|
||||
FLASH_RESERVE_START_KB 32
|
||||
|
||||
# list of files to put in ROMFS. For fmuv3 we need an IO firmware so
|
||||
# we can automatically update the IOMCU firmware on boot. The format
|
||||
|
@ -13,14 +13,14 @@ STM32_PLLM_VALUE 8
|
||||
|
||||
FLASH_SIZE_KB 1024
|
||||
|
||||
USB_STRING_PRODUCT "f745-BL"
|
||||
USB_STRING_PRODUCT "f405-BL"
|
||||
|
||||
# bootloader is installed at zero offset
|
||||
FLASH_RESERVE_START_KB 0
|
||||
|
||||
# LEDs
|
||||
PB9 LED_BOOTLOADER OUTPUT LOW GPIO(0)
|
||||
PA14 LED_ACTIVITY OUTPUT LOW GPIO(1)
|
||||
PB9 LED_BOOTLOADER OUTPUT LOW
|
||||
PA14 LED_ACTIVITY OUTPUT LOW
|
||||
define HAL_LED_ON 0
|
||||
|
||||
# the location where the bootloader will put the firmware
|
||||
|
50
libraries/AP_HAL_ChibiOS/hwdef/f745-bl/hwdef.dat
Normal file
50
libraries/AP_HAL_ChibiOS/hwdef/f745-bl/hwdef.dat
Normal file
@ -0,0 +1,50 @@
|
||||
# hw definition file for processing by chibios_pins.py
|
||||
# for f745 bootloader
|
||||
|
||||
# MCU class and specific type
|
||||
MCU STM32F7xx STM32F745xx
|
||||
|
||||
# board ID for firmware load
|
||||
APJ_BOARD_ID 254
|
||||
|
||||
# crystal frequency, setup to use external oscillator
|
||||
OSCILLATOR_HZ 8000000
|
||||
|
||||
define STM32_LSECLK 32768U
|
||||
define STM32_LSEDRV (3U << 3U)
|
||||
|
||||
define STM32_PLLSRC STM32_PLLSRC_HSE
|
||||
define STM32_PLLM_VALUE 8
|
||||
define STM32_PLLN_VALUE 432
|
||||
define STM32_PLLP_VALUE 2
|
||||
define STM32_PLLQ_VALUE 9
|
||||
|
||||
FLASH_SIZE_KB 1024
|
||||
|
||||
USB_STRING_PRODUCT "f745-BL"
|
||||
|
||||
# bootloader is installed at zero offset
|
||||
FLASH_RESERVE_START_KB 0
|
||||
|
||||
# the location where the bootloader will put the firmware
|
||||
define FLASH_BOOTLOADER_LOAD_KB 96
|
||||
|
||||
# board voltage
|
||||
STM32_VDD 330U
|
||||
|
||||
UART_ORDER OTG1
|
||||
|
||||
# PA10 IO-debug-console
|
||||
PA11 OTG_FS_DM OTG1
|
||||
PA12 OTG_FS_DP OTG1
|
||||
|
||||
PA13 JTMS-SWDIO SWD
|
||||
PA14 JTCK-SWCLK SWD
|
||||
|
||||
PA2 LED_BOOTLOADER OUTPUT HIGH
|
||||
define HAL_LED_ON 0
|
||||
|
||||
define HAL_USE_EMPTY_STORAGE
|
||||
|
||||
define HAL_STORAGE_SIZE 16384
|
||||
define STORAGE_FLASH_PAGE 1
|
46
libraries/AP_HAL_ChibiOS/hwdef/f765-bl/hwdef.dat
Normal file
46
libraries/AP_HAL_ChibiOS/hwdef/f765-bl/hwdef.dat
Normal file
@ -0,0 +1,46 @@
|
||||
# hw definition file for processing by chibios_hwdef.py
|
||||
# for F765 bootloader
|
||||
|
||||
# MCU class and specific type
|
||||
MCU STM32F7xx STM32F767xx
|
||||
|
||||
# crystal frequency
|
||||
OSCILLATOR_HZ 16000000
|
||||
|
||||
define STM32_LSECLK 32768U
|
||||
define STM32_LSEDRV (3U << 3U)
|
||||
define STM32_PLLSRC STM32_PLLSRC_HSE
|
||||
define STM32_PLLM_VALUE 8
|
||||
define STM32_PLLN_VALUE 216
|
||||
define STM32_PLLP_VALUE 2
|
||||
define STM32_PLLQ_VALUE 9
|
||||
|
||||
# board ID for firmware load
|
||||
APJ_BOARD_ID 50
|
||||
|
||||
FLASH_SIZE_KB 2048
|
||||
|
||||
# bootloader is installed at zero offset
|
||||
FLASH_RESERVE_START_KB 0
|
||||
|
||||
# the location where the bootloader will put the firmware
|
||||
define FLASH_BOOTLOADER_LOAD_KB 32
|
||||
|
||||
PC6 LED_BOOTLOADER OUTPUT HIGH
|
||||
PC7 LED_ACTIVITY OUTPUT HIGH
|
||||
define HAL_LED_ON 0
|
||||
|
||||
# board voltage
|
||||
STM32_VDD 330U
|
||||
|
||||
# order of UARTs (and USB)
|
||||
UART_ORDER OTG1
|
||||
|
||||
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
|
51
libraries/AP_HAL_ChibiOS/hwdef/f777-bl/hwdef.dat
Normal file
51
libraries/AP_HAL_ChibiOS/hwdef/f777-bl/hwdef.dat
Normal file
@ -0,0 +1,51 @@
|
||||
# hwdef for bootloader for cube-orange
|
||||
|
||||
# MCU class and specific type
|
||||
MCU STM32F7xx STM32F777xx
|
||||
|
||||
# crystal frequency
|
||||
OSCILLATOR_HZ 24000000
|
||||
|
||||
define STM32_LSECLK 32768U
|
||||
define STM32_LSEDRV (3U << 3U)
|
||||
define STM32_PLLSRC STM32_PLLSRC_HSE
|
||||
define STM32_PLLM_VALUE 24
|
||||
define STM32_PLLN_VALUE 432
|
||||
define STM32_PLLP_VALUE 2
|
||||
define STM32_PLLQ_VALUE 9
|
||||
|
||||
# board ID for firmware load
|
||||
APJ_BOARD_ID 78
|
||||
|
||||
# board voltage
|
||||
STM32_VDD 330U
|
||||
|
||||
# flash size
|
||||
FLASH_SIZE_KB 2048
|
||||
|
||||
# USB setup
|
||||
USB_VENDOR 0x2DAE # ONLY FOR USE BY ProfiCNC / HEX! NOBODY ELSE
|
||||
USB_PRODUCT 0x1001
|
||||
USB_STRING_MANUFACTURER "Hex Technology Limited"
|
||||
USB_STRING_PRODUCT "ProfiCNC CUBE Orange BL"
|
||||
USB_STRING_SERIAL "%SERIAL%"
|
||||
|
||||
# order of UARTs (and USB)
|
||||
UART_ORDER OTG1
|
||||
|
||||
# now we define the pins that USB is connected on
|
||||
PA11 OTG_FS_DM OTG1
|
||||
PA12 OTG_FS_DP OTG1
|
||||
|
||||
# these are the pins for SWD debugging with a STlinkv2 or black-magic probe
|
||||
PA13 JTMS-SWDIO SWD
|
||||
PA14 JTCK-SWCLK SWD
|
||||
|
||||
# no reserved flash for bootloader
|
||||
FLASH_RESERVE_START_KB 0
|
||||
|
||||
# the location where the bootloader will put the firmware
|
||||
define FLASH_BOOTLOADER_LOAD_KB 32
|
||||
|
||||
define HAL_USE_EMPTY_STORAGE 1
|
||||
define HAL_STORAGE_SIZE 16384
|
@ -425,6 +425,9 @@ def write_mcu_config(f):
|
||||
f.write('\n// CPU serial number (12 bytes)\n')
|
||||
f.write('#define UDID_START 0x%08x\n\n' % get_mcu_config('UDID_START', True))
|
||||
|
||||
f.write('\n// APJ board ID (for bootloaders)\n')
|
||||
f.write('#define APJ_BOARD_ID %s\n' % get_config('APJ_BOARD_ID'))
|
||||
|
||||
lib = get_mcu_lib(mcu_type)
|
||||
build_info = lib.build
|
||||
# setup build variables
|
||||
|
Loading…
Reference in New Issue
Block a user