Skip to content

Commit fcc3b70

Browse files
onur-ozkanpatrickelectric
authored andcommitted
implement buffering on serial connection reads
Adds buffered reading to `SerialConnection`. By default, the buffer size is calculated based on the baud rate and it's also configurable. This should reduce the read overhead quite significantly, especially at high baud rates. Signed-off-by: Onur Özkan <work@onurozkan.dev>
1 parent c227264 commit fcc3b70

2 files changed

Lines changed: 22 additions & 3 deletions

File tree

mavlink-core/src/connection/direct_serial.rs

Lines changed: 6 additions & 3 deletions
Original file line numberDiff line numberDiff line change
@@ -7,7 +7,7 @@ use crate::Connectable;
77
use crate::{MAVLinkMessageRaw, MavHeader, MavlinkVersion, Message, ReadVersion};
88
use core::ops::DerefMut;
99
use core::sync::atomic::{self, AtomicU8};
10-
use std::io;
10+
use std::io::{self, BufReader};
1111
use std::sync::Mutex;
1212

1313
use serialport::{DataBits, FlowControl, Parity, SerialPort, StopBits};
@@ -27,7 +27,7 @@ use config::SerialConfig;
2727
pub struct SerialConnection {
2828
// Separate ports for reading and writing as it's safe to use concurrently.
2929
// See the official ref: https://github.com/serialport/serialport-rs/blob/321f85e1886eaa1302aef8a600a631bc1c88703a/examples/duplex.rs
30-
read_port: Mutex<PeekReader<Box<dyn SerialPort>>>,
30+
read_port: Mutex<PeekReader<BufReader<Box<dyn SerialPort>>>>,
3131
write_port: Mutex<Box<dyn SerialPort>>,
3232
sequence: AtomicU8,
3333
protocol_version: MavlinkVersion,
@@ -173,8 +173,11 @@ impl Connectable for SerialConfig {
173173

174174
let write_port = read_port.try_clone()?;
175175

176+
let read_buffer_capacity = self.buffer_capacity();
177+
let buf_reader = BufReader::with_capacity(read_buffer_capacity, read_port);
178+
176179
Ok(Box::new(SerialConnection {
177-
read_port: Mutex::new(PeekReader::new(read_port)),
180+
read_port: Mutex::new(PeekReader::new(buf_reader)),
178181
write_port: Mutex::new(write_port),
179182
sequence: AtomicU8::new(0),
180183
protocol_version: MavlinkVersion::V2,

mavlink-core/src/connection/direct_serial/config.rs

Lines changed: 16 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -14,16 +14,32 @@ use core::fmt::Display;
1414
pub struct SerialConfig {
1515
pub(crate) port_name: String,
1616
pub(crate) baud_rate: u32,
17+
read_buffer_capacity: usize,
1718
}
1819

1920
impl SerialConfig {
2021
/// Creates a serial connection address with port name and baud rate.
2122
pub fn new(port_name: String, baud_rate: u32) -> Self {
23+
// Calculate a sane default buffer capacity based on the baud rate.
24+
let default_capacity = (baud_rate / 100).clamp(1024, 1024 * 8) as usize;
25+
2226
Self {
2327
port_name,
2428
baud_rate,
29+
read_buffer_capacity: default_capacity,
2530
}
2631
}
32+
33+
/// Updates the read buffer capacity.
34+
pub fn with_read_buffer_capacity(mut self, capacity: usize) -> Self {
35+
self.read_buffer_capacity = capacity;
36+
self
37+
}
38+
39+
/// Returns the configured read buffer capacity.
40+
pub fn buffer_capacity(&self) -> usize {
41+
self.read_buffer_capacity
42+
}
2743
}
2844

2945
impl Display for SerialConfig {

0 commit comments

Comments
 (0)