mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-02-23 00:04:02 -04:00
AP_IOMCU: reduce uart buffer sizes
This commit is contained in:
parent
925ce44a6c
commit
c8f24b2c71
@ -64,7 +64,7 @@ AP_IOMCU *AP_IOMCU::singleton;
|
|||||||
void AP_IOMCU::init(void)
|
void AP_IOMCU::init(void)
|
||||||
{
|
{
|
||||||
// uart runs at 1.5MBit
|
// uart runs at 1.5MBit
|
||||||
uart.begin(1500*1000, 256, 256);
|
uart.begin(1500*1000, 128, 128);
|
||||||
uart.set_blocking_writes(true);
|
uart.set_blocking_writes(true);
|
||||||
uart.set_unbuffered_writes(true);
|
uart.set_unbuffered_writes(true);
|
||||||
|
|
||||||
@ -100,7 +100,7 @@ void AP_IOMCU::thread_main(void)
|
|||||||
thread_ctx = chThdGetSelfX();
|
thread_ctx = chThdGetSelfX();
|
||||||
chEvtSignal(thread_ctx, initial_event_mask);
|
chEvtSignal(thread_ctx, initial_event_mask);
|
||||||
|
|
||||||
uart.begin(1500*1000, 256, 256);
|
uart.begin(1500*1000, 128, 128);
|
||||||
uart.set_blocking_writes(true);
|
uart.set_blocking_writes(true);
|
||||||
uart.set_unbuffered_writes(true);
|
uart.set_unbuffered_writes(true);
|
||||||
|
|
||||||
|
Loading…
Reference in New Issue
Block a user