mavlink_core/connection/direct_serial/
config.rs

1use core::fmt::Display;
2
3/// MAVLink address for a serial connection
4///
5/// # Example
6///
7/// ```ignore
8/// use mavlink::{Connectable, SerialConfig};
9///
10/// let config = SerialConfig::new("/dev/ttyTHS1".to_owned(), 115200);
11/// config.connect::<mavlink::ardupilotmega::MavMessage>();
12/// ```
13#[derive(Debug, Clone)]
14pub struct SerialConfig {
15    pub(crate) port_name: String,
16    pub(crate) baud_rate: u32,
17    read_buffer_capacity: usize,
18}
19
20impl SerialConfig {
21    /// Creates a serial connection address with port name and baud rate.
22    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
26        Self {
27            port_name,
28            baud_rate,
29            read_buffer_capacity: default_capacity,
30        }
31    }
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    }
43}
44
45impl Display for SerialConfig {
46    fn fmt(&self, f: &mut core::fmt::Formatter<'_>) -> core::fmt::Result {
47        write!(f, "serial:{}:{}", self.port_name, self.baud_rate)
48    }
49}