HAL_ChibiOS: reduce dataflash buffer size on targets with 128KB ram
This commit is contained in:
parent
932cc4bb69
commit
cfa18b8e70
@ -152,6 +152,8 @@ SPIDEV sdcard SPI3 DEVID1 SDCARD_CS MODE0 400*KHZ 25*MHZ
|
||||
define HAL_OS_FATFS_IO 1
|
||||
define HAL_BOARD_LOG_DIRECTORY "/APM/LOGS"
|
||||
define HAL_BOARD_TERRAIN_DIRECTORY "/APM/TERRAIN"
|
||||
define HAL_DATAFLASH_FILE_BUFSIZE 8
|
||||
define HAL_DATAFLASH_MAV_BUFSIZE 2
|
||||
|
||||
# 8 PWM available by default
|
||||
define BOARD_PWM_COUNT_DEFAULT 8
|
||||
|
@ -106,6 +106,8 @@ define HAL_OS_FATFS_IO 1
|
||||
# now some defines for logging and terrain data files
|
||||
define HAL_BOARD_LOG_DIRECTORY "/APM/LOGS"
|
||||
define HAL_BOARD_TERRAIN_DIRECTORY "/APM/TERRAIN"
|
||||
define HAL_DATAFLASH_FILE_BUFSIZE 8
|
||||
define HAL_DATAFLASH_MAV_BUFSIZE 2
|
||||
|
||||
# this defines the default maximum clock on I2C devices.
|
||||
define HAL_I2C_MAX_CLOCK 100000
|
||||
|
@ -109,6 +109,8 @@ define HAL_STORAGE_SIZE 15360
|
||||
define HAL_OS_FATFS_IO 1
|
||||
define HAL_BOARD_LOG_DIRECTORY "/APM/LOGS"
|
||||
define HAL_BOARD_TERRAIN_DIRECTORY "/APM/TERRAIN"
|
||||
define HAL_DATAFLASH_FILE_BUFSIZE 8
|
||||
define HAL_DATAFLASH_MAV_BUFSIZE 2
|
||||
|
||||
# define default battery setup
|
||||
define HAL_BATT_VOLT_PIN 12
|
||||
|
Loading…
Reference in New Issue
Block a user