Function mavlink::connect_async

source ยท
pub async fn connect_async<M>(
    address: &str,
) -> Result<Box<dyn AsyncMavConnection<M> + Sync + Send>, Error>
where M: Message + Sync + Send,
Expand description

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.