HAL_ChibiOS: switch more boards to 32k FRAM

this enables the parameter backup/restore on those boards, as well as
more waypoints

This is in response to a report that CUAVv5 boards can suffer from the
parameter reset issue
This commit is contained in:
Andrew Tridgell 2021-03-17 16:55:45 +11:00
parent 9a8a20f1d2
commit bbd32844d1
6 changed files with 6 additions and 6 deletions

View File

@ -429,7 +429,7 @@ define HAL_BOARD_TERRAIN_DIRECTORY "/APM/TERRAIN"
# we need to tell HAL_ChibiOS/Storage.cpp how much storage is
# available (in bytes)
define HAL_STORAGE_SIZE 16384
define HAL_STORAGE_SIZE 32768
# allow to have have a dedicated safety switch pin
define HAL_HAVE_SAFETY_SWITCH 1

View File

@ -290,7 +290,7 @@ define HAL_GPIO_LED_ON 0
# enable RAMTROM parameter storage
define HAL_STORAGE_SIZE 16384
define HAL_STORAGE_SIZE 32768
define HAL_WITH_RAMTRON 1
# allow to have have a dedicated safety switch pin

View File

@ -33,7 +33,7 @@ env OPTIMIZE -O2
FLASH_RESERVE_START_KB 128
# use FRAM for storage
define HAL_STORAGE_SIZE 16384
define HAL_STORAGE_SIZE 32768
# Enable RAMTROM parameter storage.
define HAL_WITH_RAMTRON 1

View File

@ -39,7 +39,7 @@ env OPTIMIZE -O2
FLASH_RESERVE_START_KB 96
# use FRAM for storage
define HAL_STORAGE_SIZE 16384
define HAL_STORAGE_SIZE 32768
define HAL_WITH_RAMTRON 1
# fallback storage in case FRAM is not populated

View File

@ -32,7 +32,7 @@ env OPTIMIZE -O2
# start on 2th sector (1st sector for bootloader)
FLASH_RESERVE_START_KB 128
define HAL_STORAGE_SIZE 16384
define HAL_STORAGE_SIZE 32768
# USB setup
USB_STRING_MANUFACTURER "mRo"

View File

@ -392,7 +392,7 @@ define HAL_BOARD_TERRAIN_DIRECTORY "/APM/TERRAIN"
# we need to tell HAL_ChibiOS/Storage.cpp how much storage is
# available (in bytes)
define HAL_STORAGE_SIZE 16384
define HAL_STORAGE_SIZE 32768
# allow to have have a dedicated safety switch pin
define HAL_HAVE_SAFETY_SWITCH 1