From f94c9630b80fa9f779a57562a5fd309cfb3956f4 Mon Sep 17 00:00:00 2001
From: Federico Lolli <federico123579@gmail.com>
Date: Sun, 13 Apr 2025 13:55:50 +0200
Subject: [PATCH] feat: add set_read_timeout and set_write_timeout to
 MavConnection

---
 mavlink-core/src/connection/direct_serial.rs | 15 +++++++++++++++
 mavlink-core/src/connection/file.rs          | 15 +++++++++++++++
 mavlink-core/src/connection/mod.rs           |  3 +++
 mavlink-core/src/connection/tcp.rs           | 10 ++++++++++
 mavlink-core/src/connection/udp.rs           | 11 +++++++++++
 5 files changed, 54 insertions(+)

diff --git a/mavlink-core/src/connection/direct_serial.rs b/mavlink-core/src/connection/direct_serial.rs
index 85c771b..f961359 100644
--- a/mavlink-core/src/connection/direct_serial.rs
+++ b/mavlink-core/src/connection/direct_serial.rs
@@ -7,6 +7,7 @@ use crate::{MavHeader, MavlinkVersion, Message};
 use core::ops::DerefMut;
 use std::io;
 use std::sync::Mutex;
+use std::time::Duration;
 
 use crate::error::{MessageReadError, MessageWriteError};
 use serial::{prelude::*, SystemPort};
@@ -85,6 +86,20 @@ impl<M: Message> MavConnection<M> for SerialConnection {
         self.protocol_version
     }
 
+    fn set_read_timeout(&mut self, timeout: Option<Duration>) -> io::Result<()> {
+        let mut guard = self.port.lock().unwrap();
+        let timeout = timeout.unwrap_or(Duration::ZERO);
+        guard.reader_mut().set_timeout(timeout)?;
+        Ok(())
+    }
+
+    fn set_write_timeout(&mut self, timeout: Option<Duration>) -> io::Result<()> {
+        let mut guard = self.port.lock().unwrap();
+        let timeout = timeout.unwrap_or(Duration::ZERO);
+        guard.reader_mut().set_timeout(timeout)?;
+        Ok(())
+    }
+
     #[cfg(feature = "signing")]
     fn setup_signing(&mut self, signing_data: Option<SigningConfig>) {
         self.signing_data = signing_data.map(SigningData::from_config)
diff --git a/mavlink-core/src/connection/file.rs b/mavlink-core/src/connection/file.rs
index 176a4a8..0cafa72 100644
--- a/mavlink-core/src/connection/file.rs
+++ b/mavlink-core/src/connection/file.rs
@@ -9,6 +9,7 @@ use core::ops::DerefMut;
 use std::fs::File;
 use std::io;
 use std::sync::Mutex;
+use std::time::Duration;
 
 #[cfg(not(feature = "signing"))]
 use crate::read_versioned_msg;
@@ -76,6 +77,20 @@ impl<M: Message> MavConnection<M> for FileConnection {
         self.protocol_version
     }
 
+    fn set_read_timeout(&mut self, _timeout: Option<Duration>) -> io::Result<()> {
+        Err(io::Error::new(
+            io::ErrorKind::Other,
+            "File connection does not support read timeout",
+        ))
+    }
+
+    fn set_write_timeout(&mut self, _timeout: Option<Duration>) -> io::Result<()> {
+        Err(io::Error::new(
+            io::ErrorKind::Other,
+            "File connection does not support write timeout",
+        ))
+    }
+
     #[cfg(feature = "signing")]
     fn setup_signing(&mut self, signing_data: Option<SigningConfig>) {
         self.signing_data = signing_data.map(SigningData::from_config)
diff --git a/mavlink-core/src/connection/mod.rs b/mavlink-core/src/connection/mod.rs
index 5fff34b..4861b01 100644
--- a/mavlink-core/src/connection/mod.rs
+++ b/mavlink-core/src/connection/mod.rs
@@ -30,6 +30,9 @@ pub trait MavConnection<M: Message> {
     fn set_protocol_version(&mut self, version: MavlinkVersion);
     fn protocol_version(&self) -> MavlinkVersion;
 
+    fn set_write_timeout(&mut self, timeout: Option<std::time::Duration>) -> io::Result<()>;
+    fn set_read_timeout(&mut self, timeout: Option<std::time::Duration>) -> io::Result<()>;
+
     /// Write whole frame
     fn send_frame(&self, frame: &MavFrame<M>) -> Result<usize, crate::error::MessageWriteError> {
         self.send(&frame.header, &frame.msg)
diff --git a/mavlink-core/src/connection/tcp.rs b/mavlink-core/src/connection/tcp.rs
index 3f83c2d..b251b36 100644
--- a/mavlink-core/src/connection/tcp.rs
+++ b/mavlink-core/src/connection/tcp.rs
@@ -126,6 +126,16 @@ impl<M: Message> MavConnection<M> for TcpConnection {
         self.protocol_version
     }
 
+    fn set_read_timeout(&mut self, timeout: Option<Duration>) -> io::Result<()> {
+        let mut guard = self.reader.lock().unwrap();
+        guard.reader_mut().set_read_timeout(timeout)
+    }
+
+    fn set_write_timeout(&mut self, timeout: Option<Duration>) -> io::Result<()> {
+        let guard = self.writer.lock().unwrap();
+        guard.socket.set_write_timeout(timeout)
+    }
+
     #[cfg(feature = "signing")]
     fn setup_signing(&mut self, signing_data: Option<SigningConfig>) {
         self.signing_data = signing_data.map(SigningData::from_config)
diff --git a/mavlink-core/src/connection/udp.rs b/mavlink-core/src/connection/udp.rs
index 25f5662..208a404 100644
--- a/mavlink-core/src/connection/udp.rs
+++ b/mavlink-core/src/connection/udp.rs
@@ -1,6 +1,7 @@
 //! UDP MAVLink connection
 
 use std::collections::VecDeque;
+use std::time::Duration;
 
 use crate::connectable::{UdpConnectable, UdpMode};
 use crate::connection::MavConnection;
@@ -142,6 +143,16 @@ impl<M: Message> MavConnection<M> for UdpConnection {
         self.protocol_version
     }
 
+    fn set_read_timeout(&mut self, timeout: Option<Duration>) -> io::Result<()> {
+        let mut guard = self.reader.lock().unwrap();
+        guard.reader_mut().socket.set_read_timeout(timeout)
+    }
+
+    fn set_write_timeout(&mut self, timeout: Option<Duration>) -> io::Result<()> {
+        let guard = self.writer.lock().unwrap();
+        guard.socket.set_write_timeout(timeout)
+    }
+
     #[cfg(feature = "signing")]
     fn setup_signing(&mut self, signing_data: Option<SigningConfig>) {
         self.signing_data = signing_data.map(SigningData::from_config)
-- 
GitLab