pub fn connect<M>(
address: &str,
) -> Result<Box<dyn MavConnection<M> + Sync + Send>, Error>where
M: Message,
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 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 broadcastserial:<port>:<baudrate>
to create a serial connectionfile:<path>
to extract file data
The type of the connection is determined at runtime based on the address type, so the connection is returned as a trait object.