use std::io;
use async_trait::async_trait;
#[cfg(feature = "mav2-message-signing")]
use crate::SigningConfig;
use crate::error::MessageReadError;
use crate::error::MessageWriteError;
use crate::{
MAVLinkMessageRaw, MavFrame, MavHeader, MavlinkVersion, Message, connectable::ConnectionAddress,
};
#[async_trait]
pub trait AsyncMavConnection<M: Message + Sync + Send> {
async fn recv(&self) -> Result<(MavHeader, M), MessageReadError>;
async fn recv_raw(&self) -> Result<MAVLinkMessageRaw, MessageReadError>;
async fn try_recv(&self) -> Result<(MavHeader, M), MessageReadError>;
async fn send(&self, header: &MavHeader, data: &M) -> Result<usize, MessageWriteError>;
fn set_protocol_version(&mut self, version: MavlinkVersion);
fn protocol_version(&self) -> MavlinkVersion;
fn set_allow_recv_any_version(&mut self, allow: bool);
fn allow_recv_any_version(&self) -> bool;
async fn send_frame(&self, frame: &MavFrame<M>) -> Result<usize, MessageWriteError> {
self.send(&frame.header, &frame.msg).await
}
async fn recv_frame(&self) -> Result<MavFrame<M>, MessageReadError> {
let (header, msg) = self.recv().await?;
let protocol_version = self.protocol_version();
Ok(MavFrame {
header,
msg,
protocol_version,
})
}
async fn send_default(&self, data: &M) -> Result<usize, MessageWriteError> {
let header = MavHeader::default();
self.send(&header, data).await
}
#[cfg(feature = "mav2-message-signing")]
fn setup_signing(&mut self, signing_data: Option<SigningConfig>);
}
pub async fn connect_async<M: Message + Sync + Send>(
address: &str,
) -> io::Result<Box<dyn AsyncMavConnection<M> + Sync + Send>> {
ConnectionAddress::parse_address(address)?
.connect_async::<M>()
.await
}
#[async_trait]
pub trait AsyncConnectable {
async fn connect_async<M>(&self) -> io::Result<Box<dyn AsyncMavConnection<M> + Sync + Send>>
where
M: Message + Sync + Send;
}
#[async_trait]
impl AsyncConnectable for ConnectionAddress {
async fn connect_async<M>(&self) -> io::Result<Box<dyn AsyncMavConnection<M> + Sync + Send>>
where
M: Message + Sync + Send,
{
match self {
#[cfg(feature = "transport-tcp")]
Self::Tcp(connectable) => connectable.connect_async::<M>().await,
#[cfg(feature = "transport-udp")]
Self::Udp(connectable) => connectable.connect_async::<M>().await,
#[cfg(feature = "transport-direct-serial")]
Self::Serial(connectable) => connectable.connect_async::<M>().await,
Self::File(connectable) => connectable.connect_async::<M>().await,
}
}
}