Function mavlink::connect_async
source ยท pub async fn connect_async<M>(
address: &str,
) -> Result<Box<dyn AsyncMavConnection<M> + Sync + Send>, Error>
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 connectionstcpout:<addr>:<port>
to create a TCP clientudpin:<addr>:<port>
to create a UDP server, listening for incoming packetsudpout:<addr>:<port>
to create a UDP clientudpbcast:<addr>:<port>
to create a UDP broadcastfile:<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.