HAL_ChibiOS: increase H7 serial buffer sizes

this takes better advantage of the new UART code. Log download over
USB gets to 730 kbyte/s. For comparison, with the 4.0 code on the same
H7 we get about 300 kbyte/s
This commit is contained in:
Andrew Tridgell 2021-02-20 15:59:43 +11:00
parent 3b88a3273b
commit 7af20e9ea3

View File

@ -419,7 +419,11 @@
* buffers.
*/
#if !defined(SERIAL_BUFFERS_SIZE) || defined(__DOXYGEN__)
#define SERIAL_BUFFERS_SIZE 256
#if defined(STM32H7)
#define SERIAL_BUFFERS_SIZE 512
#else
#define SERIAL_BUFFERS_SIZE 256
#endif
#endif
/*===========================================================================*/
@ -434,16 +438,24 @@
* buffers.
*/
#if !defined(SERIAL_USB_BUFFERS_SIZE) || defined(__DOXYGEN__)
#if defined(STM32H7)
#define SERIAL_USB_BUFFERS_SIZE 768
#else
#define SERIAL_USB_BUFFERS_SIZE 256
#endif
#endif
/**
* @brief Serial over USB number of buffers.
* @note The default is 2 buffers.
*/
#if !defined(SERIAL_USB_BUFFERS_NUMBER) || defined(__DOXYGEN__)
#if defined(STM32H7)
#define SERIAL_USB_BUFFERS_NUMBER 4
#else
#define SERIAL_USB_BUFFERS_NUMBER 2
#endif
#endif
/*===========================================================================*/
/* SPI driver related settings. */