mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-10 18:08:30 -04:00
AP_HAL_ChibiOS: disable UART stats based on GCS being enabled
We may need to revisit this if we are able to transfer these files over some other mechanism into the future
This commit is contained in:
parent
051104a3f7
commit
185ccaee92
@ -51,7 +51,6 @@ PA14 JTCK-SWCLK SWD
|
||||
|
||||
define HAL_NO_GPIO_IRQ
|
||||
define SERIAL_BUFFERS_SIZE 64
|
||||
define HAL_UART_STATS_ENABLED 0
|
||||
|
||||
define DMA_RESERVE_SIZE 512
|
||||
|
||||
|
@ -2675,6 +2675,11 @@ def add_apperiph_defaults(f):
|
||||
#endif
|
||||
#ifndef HAL_BARO_WIND_COMP_ENABLED
|
||||
#define HAL_BARO_WIND_COMP_ENABLED 0
|
||||
|
||||
#ifndef HAL_UART_STATS_ENABLED
|
||||
#define HAL_UART_STATS_ENABLED (HAL_GCS_ENABLED || HAL_LOGGING_ENABLED)
|
||||
#endif
|
||||
|
||||
#endif
|
||||
''')
|
||||
|
||||
|
Loading…
Reference in New Issue
Block a user