mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-02-26 09:43:57 -04:00
HAL_ChibiOS: fixed F412 ram and flash setup
This commit is contained in:
parent
7c232323da
commit
82c6d2751f
@ -308,7 +308,7 @@ def write_ldscript(fname):
|
||||
flash_reserve_end = get_config('FLASH_RESERVE_END_KB', default=0, type=int)
|
||||
|
||||
# ram size
|
||||
ram_size = get_config('RAM_SIZE_KB', default=192)
|
||||
ram_size = get_config('RAM_SIZE_KB', default=192, type=int)
|
||||
|
||||
flash_base = 0x08000000 + flash_reserve_start*1024
|
||||
flash_length = flash_size - (flash_reserve_start + flash_reserve_end)
|
||||
|
@ -23,6 +23,8 @@ STM32_PWM_USE_TIM3 TRUE
|
||||
# board voltage
|
||||
STM32_VDD 330U
|
||||
|
||||
RAM_SIZE_KB 256
|
||||
|
||||
# flash size
|
||||
FLASH_SIZE_KB 1024
|
||||
|
||||
@ -91,6 +93,8 @@ SPIDEV cypress SPI1 DEVID1 RADIO_CS MODE0 2*MHZ 2*MHZ
|
||||
SPIDEV cc2500 SPI1 DEVID1 RADIO_CS MODE0 4*MHZ 4*MHZ
|
||||
SPIDEV pixartflow SPI2 DEVID2 FLOW_CS MODE3 2*MHZ 2*MHZ
|
||||
|
||||
# reserve 16k for bootloader and 32k for storage
|
||||
FLASH_RESERVE_START_KB 48
|
||||
|
||||
define HAL_CHIBIOS_ARCH_F412 1
|
||||
|
||||
@ -104,5 +108,6 @@ define HAL_GPIO_RADIO_IRQ 2
|
||||
|
||||
define HAL_RCINPUT_WITH_AP_RADIO 1
|
||||
define STORAGE_FLASH_PAGE 1
|
||||
define HAL_STORAGE_SIZE 8192
|
||||
define HAL_STORAGE_SIZE 16384
|
||||
|
||||
|
||||
|
Loading…
Reference in New Issue
Block a user