mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-02-21 15:23:57 -04:00
HAL_ChibiOS: save some memory in f103-periph build
This commit is contained in:
parent
a7eea2a4e3
commit
f69be70772
@ -87,10 +87,10 @@ define DMA_RESERVE_SIZE 0
|
||||
define PERIPH_FW TRUE
|
||||
|
||||
# MAIN_STACK is stack of initial thread
|
||||
MAIN_STACK 0x100
|
||||
MAIN_STACK 0x80
|
||||
|
||||
# PROCESS_STACK controls stack for main thread
|
||||
PROCESS_STACK 0x600
|
||||
PROCESS_STACK 0x500
|
||||
define HAL_DISABLE_LOOP_DELAY
|
||||
|
||||
# enable CAN support
|
||||
@ -111,7 +111,8 @@ define HAL_UART_MIN_TX_SIZE 256
|
||||
define HAL_UART_MIN_RX_SIZE 128
|
||||
|
||||
define HAL_UART_STACK_SIZE 256
|
||||
define STORAGE_THD_WA_SIZE 512
|
||||
define STORAGE_THD_WA_SIZE 256
|
||||
define IO_THD_WA_SIZE 256
|
||||
|
||||
define HAL_NO_GCS
|
||||
define HAL_NO_LOGGING
|
||||
@ -128,7 +129,7 @@ COMPASS RM3100 SPI:rm3100 false ROTATION_NONE
|
||||
|
||||
define HAL_I2C_CLEAR_ON_TIMEOUT 0
|
||||
|
||||
define HAL_DEVICE_THREAD_STACK 768
|
||||
define HAL_DEVICE_THREAD_STACK 256
|
||||
|
||||
define AP_PARAM_MAX_EMBEDDED_PARAM 0
|
||||
|
||||
@ -145,3 +146,5 @@ env APP_DESCRIPTOR MissionPlanner
|
||||
|
||||
# reserve 256 bytes for comms between app and bootloader
|
||||
RAM_RESERVE_START 256
|
||||
|
||||
# define CH_DBG_ENABLE_STACK_CHECK TRUE
|
||||
|
Loading…
Reference in New Issue
Block a user