mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-10 09:58:28 -04:00
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:
parent
9a8a20f1d2
commit
bbd32844d1
@ -429,7 +429,7 @@ define HAL_BOARD_TERRAIN_DIRECTORY "/APM/TERRAIN"
|
|||||||
|
|
||||||
# we need to tell HAL_ChibiOS/Storage.cpp how much storage is
|
# we need to tell HAL_ChibiOS/Storage.cpp how much storage is
|
||||||
# available (in bytes)
|
# available (in bytes)
|
||||||
define HAL_STORAGE_SIZE 16384
|
define HAL_STORAGE_SIZE 32768
|
||||||
|
|
||||||
# allow to have have a dedicated safety switch pin
|
# allow to have have a dedicated safety switch pin
|
||||||
define HAL_HAVE_SAFETY_SWITCH 1
|
define HAL_HAVE_SAFETY_SWITCH 1
|
||||||
|
@ -290,7 +290,7 @@ define HAL_GPIO_LED_ON 0
|
|||||||
|
|
||||||
|
|
||||||
# enable RAMTROM parameter storage
|
# enable RAMTROM parameter storage
|
||||||
define HAL_STORAGE_SIZE 16384
|
define HAL_STORAGE_SIZE 32768
|
||||||
define HAL_WITH_RAMTRON 1
|
define HAL_WITH_RAMTRON 1
|
||||||
|
|
||||||
# allow to have have a dedicated safety switch pin
|
# allow to have have a dedicated safety switch pin
|
||||||
|
@ -33,7 +33,7 @@ env OPTIMIZE -O2
|
|||||||
FLASH_RESERVE_START_KB 128
|
FLASH_RESERVE_START_KB 128
|
||||||
|
|
||||||
# use FRAM for storage
|
# use FRAM for storage
|
||||||
define HAL_STORAGE_SIZE 16384
|
define HAL_STORAGE_SIZE 32768
|
||||||
|
|
||||||
# Enable RAMTROM parameter storage.
|
# Enable RAMTROM parameter storage.
|
||||||
define HAL_WITH_RAMTRON 1
|
define HAL_WITH_RAMTRON 1
|
||||||
|
@ -39,7 +39,7 @@ env OPTIMIZE -O2
|
|||||||
FLASH_RESERVE_START_KB 96
|
FLASH_RESERVE_START_KB 96
|
||||||
|
|
||||||
# use FRAM for storage
|
# use FRAM for storage
|
||||||
define HAL_STORAGE_SIZE 16384
|
define HAL_STORAGE_SIZE 32768
|
||||||
define HAL_WITH_RAMTRON 1
|
define HAL_WITH_RAMTRON 1
|
||||||
|
|
||||||
# fallback storage in case FRAM is not populated
|
# fallback storage in case FRAM is not populated
|
||||||
|
@ -32,7 +32,7 @@ env OPTIMIZE -O2
|
|||||||
# start on 2th sector (1st sector for bootloader)
|
# start on 2th sector (1st sector for bootloader)
|
||||||
FLASH_RESERVE_START_KB 128
|
FLASH_RESERVE_START_KB 128
|
||||||
|
|
||||||
define HAL_STORAGE_SIZE 16384
|
define HAL_STORAGE_SIZE 32768
|
||||||
|
|
||||||
# USB setup
|
# USB setup
|
||||||
USB_STRING_MANUFACTURER "mRo"
|
USB_STRING_MANUFACTURER "mRo"
|
||||||
|
@ -392,7 +392,7 @@ define HAL_BOARD_TERRAIN_DIRECTORY "/APM/TERRAIN"
|
|||||||
|
|
||||||
# we need to tell HAL_ChibiOS/Storage.cpp how much storage is
|
# we need to tell HAL_ChibiOS/Storage.cpp how much storage is
|
||||||
# available (in bytes)
|
# available (in bytes)
|
||||||
define HAL_STORAGE_SIZE 16384
|
define HAL_STORAGE_SIZE 32768
|
||||||
|
|
||||||
# allow to have have a dedicated safety switch pin
|
# allow to have have a dedicated safety switch pin
|
||||||
define HAL_HAVE_SAFETY_SWITCH 1
|
define HAL_HAVE_SAFETY_SWITCH 1
|
||||||
|
Loading…
Reference in New Issue
Block a user