AP_Periph: switched to 1kHz clock for f303-periph

and use CAN RX buffer size of 64.

This makes for more efficient CPU usage on f3, and fixes an issue with
lost CAN parameter replies causing timeouts in the CAN parameter
download protocol
This commit is contained in:
Andrew Tridgell 2020-12-02 10:40:13 +11:00
parent 287e9350a5
commit 6765265a3b
1 changed files with 2 additions and 3 deletions

View File

@ -22,7 +22,7 @@ define HAL_WATCHDOG_ENABLED_DEFAULT true
# crystal frequency
OSCILLATOR_HZ 8000000
define CH_CFG_ST_FREQUENCY 100000
define CH_CFG_ST_FREQUENCY 1000
define CH_CFG_ST_TIMEDELTA 0
# assume the 256k flash part for now
@ -107,7 +107,6 @@ define IO_THD_WA_SIZE 512
define HAL_NO_GCS
define HAL_NO_LOGGING
//define HAL_NO_MONITOR_THREAD
define HAL_MINIMIZE_FEATURES 0
@ -140,4 +139,4 @@ RAM_RESERVE_START 256
env ROMFS_UNCOMPRESSED True
# reduce the number of CAN RX Buffer
define HAL_CAN_RX_QUEUE_SIZE 32
define HAL_CAN_RX_QUEUE_SIZE 64