HAL_ChibiOS: reduce memory used by serial buffers

this does not appear to affect log download speed. It saves about 27k
of memory
This commit is contained in:
Andrew Tridgell 2018-08-01 12:20:28 +10:00
parent 8c3c785f96
commit 765e00faf1
2 changed files with 3 additions and 3 deletions

View File

@ -129,8 +129,8 @@ void UARTDriver::begin(uint32_t b, uint16_t rxS, uint16_t txS)
if (sdef.serial == nullptr) {
return;
}
uint16_t min_tx_buffer = 4096;
uint16_t min_rx_buffer = 1024;
uint16_t min_tx_buffer = 1024;
uint16_t min_rx_buffer = 512;
// on PX4 we have enough memory to have a larger transmit and
// receive buffer for all ports. This means we don't get delays
// while waiting to write GPS config packets

View File

@ -320,7 +320,7 @@
* buffers.
*/
#if !defined(SERIAL_BUFFERS_SIZE) || defined(__DOXYGEN__)
#define SERIAL_BUFFERS_SIZE 1024
#define SERIAL_BUFFERS_SIZE 512
#endif
/*===========================================================================*/