Skip to content
New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

async connections #276

Merged
merged 7 commits into from
Sep 9, 2024
Merged
Show file tree
Hide file tree
Changes from all commits
Commits
File filter

Filter by extension

Filter by extension


Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
8 changes: 6 additions & 2 deletions mavlink-core/Cargo.toml
Original file line number Diff line number Diff line change
Expand Up @@ -26,8 +26,9 @@ embedded-io-async = { version = "0.6.1", optional = true }
serde = { version = "1.0.115", optional = true, features = ["derive"] }
serde_arrays = { version = "0.1.0", optional = true }
serial = { version = "0.4", optional = true }
tokio = { version = "1.0", default-features = false, features = ["io-util"], optional = true }
tokio = { version = "1.0", default-features = false, features = ["io-util", "net", "sync", "fs"], optional = true }
sha2 = { version = "0.10", optional = true }
async-trait = { version = "0.1.18", optional = true }

[features]
"std" = ["byteorder/std"]
Expand All @@ -40,6 +41,9 @@ sha2 = { version = "0.10", optional = true }
"embedded" = ["dep:embedded-io", "dep:embedded-io-async"]
"embedded-hal-02" = ["dep:nb", "dep:embedded-hal-02"]
"serde" = ["dep:serde", "dep:serde_arrays"]
"tokio-1" = ["dep:tokio"]
"tokio-1" = ["dep:tokio", "dep:async-trait"]
"signing" = ["dep:sha2"]
default = ["std", "tcp", "udp", "direct-serial", "serde"]

[dev-dependencies]
tokio = { version = "1.0", default-features = false, features = ["io-util", "net", "sync", "fs", "macros", "rt"] }
83 changes: 83 additions & 0 deletions mavlink-core/src/async_connection/file.rs
Original file line number Diff line number Diff line change
@@ -0,0 +1,83 @@
//! Async File MAVLINK connection

use core::ops::DerefMut;

use super::AsyncMavConnection;
use crate::error::{MessageReadError, MessageWriteError};

use crate::{async_peek_reader::AsyncPeekReader, MavHeader, MavlinkVersion, Message};

use tokio::fs::File;
use tokio::io;
use tokio::sync::Mutex;

#[cfg(not(feature = "signing"))]
use crate::read_versioned_msg_async;

#[cfg(feature = "signing")]
use crate::{read_versioned_msg_async_signed, SigningConfig, SigningData};

pub async fn open(file_path: &str) -> io::Result<AsyncFileConnection> {
let file = File::open(file_path).await?;
Ok(AsyncFileConnection {
file: Mutex::new(AsyncPeekReader::new(file)),
protocol_version: MavlinkVersion::V2,
#[cfg(feature = "signing")]
signing_data: None,
})
}

pub struct AsyncFileConnection {
file: Mutex<AsyncPeekReader<File>>,
protocol_version: MavlinkVersion,

#[cfg(feature = "signing")]
signing_data: Option<SigningData>,
}

#[async_trait::async_trait]
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;

loop {
#[cfg(not(feature = "signing"))]
let result = read_versioned_msg_async(file.deref_mut(), self.protocol_version).await;
#[cfg(feature = "signing")]
let result = read_versioned_msg_async_signed(
file.deref_mut(),
self.protocol_version,
self.signing_data.as_ref(),
)
.await;
match result {
ok @ Ok(..) => {
return ok;
}
Err(MessageReadError::Io(e)) => {
if e.kind() == io::ErrorKind::UnexpectedEof {
return Err(MessageReadError::Io(e));
}
}
_ => {}
}
}
}

async fn send(&self, _header: &MavHeader, _data: &M) -> Result<usize, MessageWriteError> {
Ok(0)
}

fn set_protocol_version(&mut self, version: MavlinkVersion) {
self.protocol_version = version;
}

fn get_protocol_version(&self) -> MavlinkVersion {
self.protocol_version
}

#[cfg(feature = "signing")]
fn setup_signing(&mut self, signing_data: Option<SigningConfig>) {
self.signing_data = signing_data.map(SigningData::from_config)
}
}
125 changes: 125 additions & 0 deletions mavlink-core/src/async_connection/mod.rs
Original file line number Diff line number Diff line change
@@ -0,0 +1,125 @@
use tokio::io;

use crate::{MavFrame, MavHeader, MavlinkVersion, Message};

#[cfg(feature = "tcp")]
mod tcp;

#[cfg(feature = "udp")]
mod udp;

mod file;

#[cfg(feature = "signing")]
use crate::SigningConfig;

/// An async MAVLink connection
#[async_trait::async_trait]
pub trait AsyncMavConnection<M: Message + Sync + Send> {
/// Receive a mavlink message.
///
/// Yield until a valid frame is received, ignoring invalid messages.
async fn recv(&self) -> Result<(MavHeader, M), crate::error::MessageReadError>;

/// Send a mavlink message
async fn send(
&self,
header: &MavHeader,
data: &M,
) -> Result<usize, crate::error::MessageWriteError>;

fn set_protocol_version(&mut self, version: MavlinkVersion);
fn get_protocol_version(&self) -> MavlinkVersion;

/// Write whole frame
async fn send_frame(
&self,
frame: &MavFrame<M>,
) -> Result<usize, crate::error::MessageWriteError> {
self.send(&frame.header, &frame.msg).await
}

/// Read whole frame
async fn recv_frame(&self) -> Result<MavFrame<M>, crate::error::MessageReadError> {
let (header, msg) = self.recv().await?;
let protocol_version = self.get_protocol_version();
Ok(MavFrame {
header,
msg,
protocol_version,
})
}

/// Send a message with default header
async fn send_default(&self, data: &M) -> Result<usize, crate::error::MessageWriteError> {
let header = MavHeader::default();
self.send(&header, data).await
}

/// Setup secret key used for message signing, or disable message signing
#[cfg(feature = "signing")]
fn setup_signing(&mut self, signing_data: Option<SigningConfig>);
}

/// Connect asynchronously to a MAVLink node by address string.
///
/// The address must be in one of the following formats:
///
/// * `tcpin:<addr>:<port>` to create a TCP server, listening for incoming connections
/// * `tcpout:<addr>:<port>` to create a TCP client
/// * `udpin:<addr>:<port>` to create a UDP server, listening for incoming packets
/// * `udpout:<addr>:<port>` to create a UDP client
/// * `udpbcast:<addr>:<port>` to create a UDP broadcast
/// * `file:<path>` to extract file data
///
/// Serial is currently not supported for async connections, use [`crate::connect`] instead.
/// The type of the connection is determined at runtime based on the address type, so the
/// connection is returned as a trait object.
pub async fn connect_async<M: Message + Sync + Send>(
address: &str,
) -> io::Result<Box<dyn AsyncMavConnection<M> + Sync + Send>> {
let protocol_err = Err(io::Error::new(
io::ErrorKind::AddrNotAvailable,
"Protocol unsupported",
));

if cfg!(feature = "tcp") && address.starts_with("tcp") {
#[cfg(feature = "tcp")]
{
tcp::select_protocol(address).await
}
#[cfg(not(feature = "tcp"))]
{
protocol_err
}
} else if cfg!(feature = "udp") && address.starts_with("udp") {
#[cfg(feature = "udp")]
{
udp::select_protocol(address).await
}
#[cfg(not(feature = "udp"))]
{
protocol_err
}
} else if address.starts_with("file") {
Ok(Box::new(file::open(&address["file:".len()..]).await?))
} else {
protocol_err
}
}

/// Returns the socket address for the given address.
pub(crate) fn get_socket_addr<T: std::net::ToSocketAddrs>(
address: T,
) -> Result<std::net::SocketAddr, io::Error> {
let addr = match address.to_socket_addrs()?.next() {
Some(addr) => addr,
None => {
return Err(io::Error::new(
io::ErrorKind::Other,
"Host address lookup failed",
));
}
};
Ok(addr)
}
156 changes: 156 additions & 0 deletions mavlink-core/src/async_connection/tcp.rs
Original file line number Diff line number Diff line change
@@ -0,0 +1,156 @@
//! Async TCP MAVLink connection

use super::{get_socket_addr, AsyncMavConnection};
use crate::async_peek_reader::AsyncPeekReader;
use crate::{MavHeader, MavlinkVersion, Message};

use core::ops::DerefMut;
use tokio::io;
use tokio::net::tcp::{OwnedReadHalf, OwnedWriteHalf};
use tokio::net::{TcpListener, TcpStream};
use tokio::sync::Mutex;

#[cfg(not(feature = "signing"))]
use crate::{read_versioned_msg_async, write_versioned_msg_async};
#[cfg(feature = "signing")]
use crate::{
read_versioned_msg_async_signed, write_versioned_msg_async_signed, SigningConfig, SigningData,
};

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:") {
tcpout(address).await
} else if let Some(address) = address.strip_prefix("tcpin:") {
tcpin(address).await
} else {
Err(io::Error::new(
io::ErrorKind::AddrNotAvailable,
"Protocol unsupported",
))
};

Ok(Box::new(connection?))
}

pub async fn tcpout<T: std::net::ToSocketAddrs>(address: T) -> io::Result<AsyncTcpConnection> {
let addr = get_socket_addr(address)?;

let socket = TcpStream::connect(addr).await?;

let (reader, writer) = socket.into_split();

Ok(AsyncTcpConnection {
reader: Mutex::new(AsyncPeekReader::new(reader)),
writer: Mutex::new(TcpWrite {
socket: writer,
sequence: 0,
}),
protocol_version: MavlinkVersion::V2,
#[cfg(feature = "signing")]
signing_data: None,
})
}

pub async fn tcpin<T: std::net::ToSocketAddrs>(address: T) -> io::Result<AsyncTcpConnection> {
let addr = get_socket_addr(address)?;
let listener = TcpListener::bind(addr).await?;

//For now we only accept one incoming stream: this yields until we get one
match listener.accept().await {
Ok((socket, _)) => {
let (reader, writer) = socket.into_split();
return Ok(AsyncTcpConnection {
reader: Mutex::new(AsyncPeekReader::new(reader)),
writer: Mutex::new(TcpWrite {
socket: writer,
sequence: 0,
}),
protocol_version: MavlinkVersion::V2,
#[cfg(feature = "signing")]
signing_data: None,
});
}
Err(e) => {
//TODO don't println in lib
println!("listener err: {e}");
}
}
Err(io::Error::new(
io::ErrorKind::NotConnected,
"No incoming connections!",
))
}

pub struct AsyncTcpConnection {
reader: Mutex<AsyncPeekReader<OwnedReadHalf>>,
writer: Mutex<TcpWrite>,
protocol_version: MavlinkVersion,
#[cfg(feature = "signing")]
signing_data: Option<SigningData>,
}

struct TcpWrite {
socket: OwnedWriteHalf,
sequence: u8,
}

#[async_trait::async_trait]
impl<M: Message + Sync + Send> AsyncMavConnection<M> for AsyncTcpConnection {
async fn recv(&self) -> Result<(MavHeader, M), crate::error::MessageReadError> {
let mut reader = self.reader.lock().await;
#[cfg(not(feature = "signing"))]
let result = read_versioned_msg_async(reader.deref_mut(), self.protocol_version).await;
#[cfg(feature = "signing")]
let result = read_versioned_msg_async_signed(
reader.deref_mut(),
self.protocol_version,
self.signing_data.as_ref(),
)
.await;
result
}

async fn send(
&self,
header: &MavHeader,
data: &M,
) -> Result<usize, crate::error::MessageWriteError> {
let mut lock = self.writer.lock().await;

let header = MavHeader {
sequence: lock.sequence,
system_id: header.system_id,
component_id: header.component_id,
};

lock.sequence = lock.sequence.wrapping_add(1);
#[cfg(not(feature = "signing"))]
let result =
write_versioned_msg_async(&mut lock.socket, self.protocol_version, header, data).await;
#[cfg(feature = "signing")]
let result = write_versioned_msg_async_signed(
&mut lock.socket,
self.protocol_version,
header,
data,
self.signing_data.as_ref(),
)
.await;
result
}

fn set_protocol_version(&mut self, version: MavlinkVersion) {
self.protocol_version = version;
}

fn get_protocol_version(&self) -> MavlinkVersion {
self.protocol_version
}

#[cfg(feature = "signing")]
fn setup_signing(&mut self, signing_data: Option<SigningConfig>) {
self.signing_data = signing_data.map(SigningData::from_config)
}
}
Loading
Loading