pub fn connect<M: Message + Sync + Send>(address: &str) -> Result<Connection<M>>Available on crate feature
std only.Expand description
Connect 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 an incoming connectiontcpout:<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 broadcastserial:<port>:<baudrate>to create a serial connectionfile:<path>to extract file data, writing to such a connection does nothing
The type of the connection is determined at runtime based on the address type
and the resulting Connection enum stores the concrete transport.
ยงErrors
AddrNotAvailableif the address string could not be parsed as a valid MAVLink address- When the connection could not be established a corresponding
io::Erroris returned