mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-03 14:38:30 -04:00
hwdef: update FRAM size to 32768
This commit is contained in:
parent
b87cad8f6d
commit
66df41358b
@ -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"
|
||||||
|
Loading…
Reference in New Issue
Block a user