diff --git a/mavlink-core/src/async_connection/file.rs b/mavlink-core/src/async_connection/file.rs
index 9b1c90af3ae9d4f0aeb4e543dec0aa5f1aa8abde..852273649fb70b1a1ad6db63bdd5c08526aab1c1 100644
--- a/mavlink-core/src/async_connection/file.rs
+++ b/mavlink-core/src/async_connection/file.rs
@@ -36,7 +36,7 @@ pub struct AsyncFileConnection {
 }
 
 #[async_trait::async_trait]
-impl<M: Message + Sync> AsyncMavConnection<M> for AsyncFileConnection {
+impl<M: Message + Sync + Send> AsyncMavConnection<M> for AsyncFileConnection {
     async fn recv(&self) -> Result<(MavHeader, M), crate::error::MessageReadError> {
         let mut file = self.file.lock().await;
 
diff --git a/mavlink-core/src/async_connection/mod.rs b/mavlink-core/src/async_connection/mod.rs
index ed727ec93b456bb77294d1119322e69048f83bd1..a708a67328d5c9b9e2fe58c1ba503c737f1c4896 100644
--- a/mavlink-core/src/async_connection/mod.rs
+++ b/mavlink-core/src/async_connection/mod.rs
@@ -15,7 +15,7 @@ use crate::SigningConfig;
 
 /// An async MAVLink connection
 #[async_trait::async_trait]
-pub trait AsyncMavConnection<M: Message + Sync> {
+pub trait AsyncMavConnection<M: Message + Sync + Send> {
     /// Receive a mavlink message.
     ///
     /// Wait until a valid frame is received, ignoring invalid messages.
diff --git a/mavlink-core/src/async_connection/tcp.rs b/mavlink-core/src/async_connection/tcp.rs
index e05d70455bca6fd5e0053fcad55bca210c28a72a..e8171c7961744fa75cbc4952f4ea8df107b5eb3c 100644
--- a/mavlink-core/src/async_connection/tcp.rs
+++ b/mavlink-core/src/async_connection/tcp.rs
@@ -17,7 +17,7 @@ use crate::{
 
 /// TCP MAVLink connection
 
-pub async fn select_protocol<M: Message + Sync>(
+pub async fn select_protocol<M: Message + Sync + Send>(
     address: &str,
 ) -> io::Result<Box<dyn AsyncMavConnection<M> + Sync + Send>> {
     let connection = if let Some(address) = address.strip_prefix("tcpout:") {
@@ -97,7 +97,7 @@ struct TcpWrite {
 }
 
 #[async_trait::async_trait]
-impl<M: Message + Sync> AsyncMavConnection<M> for TcpConnection {
+impl<M: Message + Sync + Send> AsyncMavConnection<M> for TcpConnection {
     async fn recv(&self) -> Result<(MavHeader, M), crate::error::MessageReadError> {
         let mut reader = self.reader.lock().await;
         #[cfg(not(feature = "signing"))]