mirror of https://github.com/ArduPilot/ardupilot
HAL_ChibiOS: fixed flash storage in ZubaxGNSS
This commit is contained in:
parent
4677dca834
commit
5efaea2d92
|
@ -26,6 +26,9 @@ define CH_CFG_ST_FREQUENCY 1000
|
|||
|
||||
FLASH_SIZE_KB 256
|
||||
|
||||
# reserve space for params
|
||||
FLASH_RESERVE_END_KB 2
|
||||
|
||||
# USART3 for debug
|
||||
#STDOUT_SERIAL SD3
|
||||
#STDOUT_BAUDRATE 115200
|
||||
|
|
|
@ -12,8 +12,8 @@ define CAN_APP_NODE_NAME "org.ardupilot.ap_periph_ZubaxGNSS"
|
|||
# bootloader starts firmware at 34k
|
||||
FLASH_RESERVE_START_KB 34
|
||||
|
||||
# store parameters in pages 32 and 33
|
||||
define STORAGE_FLASH_PAGE 32
|
||||
# store parameters in last 2 pages
|
||||
define STORAGE_FLASH_PAGE 126
|
||||
define HAL_STORAGE_SIZE 800
|
||||
|
||||
# board ID for firmware load
|
||||
|
@ -29,6 +29,9 @@ define CH_CFG_ST_FREQUENCY 1000
|
|||
|
||||
FLASH_SIZE_KB 256
|
||||
|
||||
# reserve space for params
|
||||
FLASH_RESERVE_END_KB 2
|
||||
|
||||
# USART3 for debug
|
||||
STDOUT_SERIAL SD3
|
||||
STDOUT_BAUDRATE 115200
|
||||
|
@ -94,11 +97,9 @@ define HAL_NO_GPIO_IRQ
|
|||
|
||||
define CH_CFG_ST_TIMEDELTA 0
|
||||
define SERIAL_BUFFERS_SIZE 512
|
||||
define HAL_USE_EMPTY_IO TRUE
|
||||
define PORT_INT_REQUIRED_STACK 64
|
||||
|
||||
# avoid timer and RCIN threads to save memory
|
||||
define HAL_NO_TIMER_THREAD
|
||||
# avoid RCIN thread to save memory
|
||||
define HAL_NO_RCIN_THREAD
|
||||
|
||||
#defined to turn off undef warnings
|
||||
|
@ -131,7 +132,6 @@ define STORAGE_THD_WA_SIZE 512
|
|||
define HAL_MINIMIZE_FEATURES 0
|
||||
|
||||
define HAL_BUILD_AP_PERIPH
|
||||
define HAL_USE_EMPTY_STORAGE 1
|
||||
|
||||
define HAL_I2C_CLEAR_ON_TIMEOUT 0
|
||||
|
||||
|
|
Loading…
Reference in New Issue