use core::fmt::Display;
use core::marker::PhantomData;
use std::io;
#[cfg(feature = "transport-tcp")]
use super::tcp::TcpConnection;
#[cfg(feature = "transport-udp")]
use super::udp::UdpConnection;
#[cfg(feature = "transport-direct-serial")]
use super::direct_serial::SerialConnection;
use super::file::FileConnection;
#[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,
};
pub trait MavConnection<M: Message> {
fn recv(&self) -> Result<(MavHeader, M), MessageReadError>;
fn recv_raw(&self) -> Result<MAVLinkMessageRaw, MessageReadError>;
fn try_recv(&self) -> Result<(MavHeader, M), MessageReadError>;
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;
fn send_frame(&self, frame: &MavFrame<M>) -> Result<usize, MessageWriteError> {
self.send(&frame.header, &frame.msg)
}
fn recv_frame(&self) -> Result<MavFrame<M>, MessageReadError> {
let (header, msg) = self.recv()?;
let protocol_version = self.protocol_version();
Ok(MavFrame {
header,
msg,
protocol_version,
})
}
fn send_default(&self, data: &M) -> Result<usize, MessageWriteError> {
let header = MavHeader::default();
self.send(&header, data)
}
#[cfg(feature = "mav2-message-signing")]
fn setup_signing(&mut self, signing_data: Option<SigningConfig>);
}
pub struct Connection<M: Message> {
inner: ConnectionInner,
_p: PhantomData<M>,
}
enum ConnectionInner {
#[cfg(feature = "transport-tcp")]
Tcp(TcpConnection),
#[cfg(feature = "transport-udp")]
Udp(UdpConnection),
#[cfg(feature = "transport-direct-serial")]
Serial(SerialConnection),
File(FileConnection),
}
impl<M: Message> Connection<M> {
fn new(inner: ConnectionInner) -> Self {
Self {
inner,
_p: PhantomData,
}
}
}
#[cfg(feature = "transport-tcp")]
impl<M: Message> From<TcpConnection> for Connection<M> {
fn from(value: TcpConnection) -> Self {
Self::new(ConnectionInner::Tcp(value))
}
}
#[cfg(feature = "transport-udp")]
impl<M: Message> From<UdpConnection> for Connection<M> {
fn from(value: UdpConnection) -> Self {
Self::new(ConnectionInner::Udp(value))
}
}
#[cfg(feature = "transport-direct-serial")]
impl<M: Message> From<SerialConnection> for Connection<M> {
fn from(value: SerialConnection) -> Self {
Self::new(ConnectionInner::Serial(value))
}
}
impl<M: Message> From<FileConnection> for Connection<M> {
fn from(value: FileConnection) -> Self {
Self::new(ConnectionInner::File(value))
}
}
impl<M: Message> MavConnection<M> for Connection<M> {
fn recv(&self) -> Result<(MavHeader, M), MessageReadError> {
match &self.inner {
#[cfg(feature = "transport-tcp")]
ConnectionInner::Tcp(conn) => <TcpConnection as MavConnection<M>>::recv(conn),
#[cfg(feature = "transport-udp")]
ConnectionInner::Udp(conn) => <UdpConnection as MavConnection<M>>::recv(conn),
#[cfg(feature = "transport-direct-serial")]
ConnectionInner::Serial(conn) => <SerialConnection as MavConnection<M>>::recv(conn),
ConnectionInner::File(conn) => <FileConnection as MavConnection<M>>::recv(conn),
}
}
fn recv_raw(&self) -> Result<MAVLinkMessageRaw, MessageReadError> {
match &self.inner {
#[cfg(feature = "transport-tcp")]
ConnectionInner::Tcp(conn) => <TcpConnection as MavConnection<M>>::recv_raw(conn),
#[cfg(feature = "transport-udp")]
ConnectionInner::Udp(conn) => <UdpConnection as MavConnection<M>>::recv_raw(conn),
#[cfg(feature = "transport-direct-serial")]
ConnectionInner::Serial(conn) => <SerialConnection as MavConnection<M>>::recv_raw(conn),
ConnectionInner::File(conn) => <FileConnection as MavConnection<M>>::recv_raw(conn),
}
}
fn try_recv(&self) -> Result<(MavHeader, M), MessageReadError> {
match &self.inner {
#[cfg(feature = "transport-tcp")]
ConnectionInner::Tcp(conn) => <TcpConnection as MavConnection<M>>::try_recv(conn),
#[cfg(feature = "transport-udp")]
ConnectionInner::Udp(conn) => <UdpConnection as MavConnection<M>>::try_recv(conn),
#[cfg(feature = "transport-direct-serial")]
ConnectionInner::Serial(conn) => <SerialConnection as MavConnection<M>>::try_recv(conn),
ConnectionInner::File(conn) => <FileConnection as MavConnection<M>>::try_recv(conn),
}
}
fn send(&self, header: &MavHeader, data: &M) -> Result<usize, MessageWriteError> {
match &self.inner {
#[cfg(feature = "transport-tcp")]
ConnectionInner::Tcp(conn) => {
<TcpConnection as MavConnection<M>>::send(conn, header, data)
}
#[cfg(feature = "transport-udp")]
ConnectionInner::Udp(conn) => {
<UdpConnection as MavConnection<M>>::send(conn, header, data)
}
#[cfg(feature = "transport-direct-serial")]
ConnectionInner::Serial(conn) => {
<SerialConnection as MavConnection<M>>::send(conn, header, data)
}
ConnectionInner::File(conn) => {
<FileConnection as MavConnection<M>>::send(conn, header, data)
}
}
}
fn set_protocol_version(&mut self, version: MavlinkVersion) {
match &mut self.inner {
#[cfg(feature = "transport-tcp")]
ConnectionInner::Tcp(conn) => {
<TcpConnection as MavConnection<M>>::set_protocol_version(conn, version);
}
#[cfg(feature = "transport-udp")]
ConnectionInner::Udp(conn) => {
<UdpConnection as MavConnection<M>>::set_protocol_version(conn, version);
}
#[cfg(feature = "transport-direct-serial")]
ConnectionInner::Serial(conn) => {
<SerialConnection as MavConnection<M>>::set_protocol_version(conn, version);
}
ConnectionInner::File(conn) => {
<FileConnection as MavConnection<M>>::set_protocol_version(conn, version);
}
}
}
fn protocol_version(&self) -> MavlinkVersion {
match &self.inner {
#[cfg(feature = "transport-tcp")]
ConnectionInner::Tcp(conn) => {
<TcpConnection as MavConnection<M>>::protocol_version(conn)
}
#[cfg(feature = "transport-udp")]
ConnectionInner::Udp(conn) => {
<UdpConnection as MavConnection<M>>::protocol_version(conn)
}
#[cfg(feature = "transport-direct-serial")]
ConnectionInner::Serial(conn) => {
<SerialConnection as MavConnection<M>>::protocol_version(conn)
}
ConnectionInner::File(conn) => {
<FileConnection as MavConnection<M>>::protocol_version(conn)
}
}
}
fn set_allow_recv_any_version(&mut self, allow: bool) {
match &mut self.inner {
#[cfg(feature = "transport-tcp")]
ConnectionInner::Tcp(conn) => {
<TcpConnection as MavConnection<M>>::set_allow_recv_any_version(conn, allow);
}
#[cfg(feature = "transport-udp")]
ConnectionInner::Udp(conn) => {
<UdpConnection as MavConnection<M>>::set_allow_recv_any_version(conn, allow);
}
#[cfg(feature = "transport-direct-serial")]
ConnectionInner::Serial(conn) => {
<SerialConnection as MavConnection<M>>::set_allow_recv_any_version(conn, allow);
}
ConnectionInner::File(conn) => {
<FileConnection as MavConnection<M>>::set_allow_recv_any_version(conn, allow);
}
}
}
fn allow_recv_any_version(&self) -> bool {
match &self.inner {
#[cfg(feature = "transport-tcp")]
ConnectionInner::Tcp(conn) => {
<TcpConnection as MavConnection<M>>::allow_recv_any_version(conn)
}
#[cfg(feature = "transport-udp")]
ConnectionInner::Udp(conn) => {
<UdpConnection as MavConnection<M>>::allow_recv_any_version(conn)
}
#[cfg(feature = "transport-direct-serial")]
ConnectionInner::Serial(conn) => {
<SerialConnection as MavConnection<M>>::allow_recv_any_version(conn)
}
ConnectionInner::File(conn) => {
<FileConnection as MavConnection<M>>::allow_recv_any_version(conn)
}
}
}
#[cfg(feature = "mav2-message-signing")]
fn setup_signing(&mut self, signing_data: Option<SigningConfig>) {
let mut signing_data = signing_data;
match &mut self.inner {
#[cfg(feature = "transport-tcp")]
ConnectionInner::Tcp(conn) => {
<TcpConnection as MavConnection<M>>::setup_signing(conn, signing_data.take());
}
#[cfg(feature = "transport-udp")]
ConnectionInner::Udp(conn) => {
<UdpConnection as MavConnection<M>>::setup_signing(conn, signing_data.take());
}
#[cfg(feature = "transport-direct-serial")]
ConnectionInner::Serial(conn) => {
<SerialConnection as MavConnection<M>>::setup_signing(conn, signing_data.take());
}
ConnectionInner::File(conn) => {
<FileConnection as MavConnection<M>>::setup_signing(conn, signing_data.take());
}
}
}
}
pub fn connect<M: Message + Sync + Send>(address: &str) -> io::Result<Connection<M>> {
ConnectionAddress::parse_address(address)?.connect::<M>()
}
pub trait Connectable: Display {
fn connect<M: Message>(&self) -> io::Result<Connection<M>>;
}
impl Connectable for ConnectionAddress {
fn connect<M>(&self) -> std::io::Result<Connection<M>>
where
M: Message,
{
match self {
#[cfg(feature = "transport-tcp")]
Self::Tcp(config) => config.connect::<M>(),
#[cfg(feature = "transport-udp")]
Self::Udp(config) => config.connect::<M>(),
#[cfg(feature = "transport-direct-serial")]
Self::Serial(config) => config.connect::<M>(),
Self::File(config) => config.connect::<M>(),
}
}
}