pub struct Connection<M>where
M: Message,{ /* private fields */ }Expand description
Concrete MAVLink connection returned by connect.
Trait Implementations§
Source§impl<M> From<FileConnection> for Connection<M>where
M: Message,
impl<M> From<FileConnection> for Connection<M>where
M: Message,
Source§fn from(value: FileConnection) -> Connection<M>
fn from(value: FileConnection) -> Connection<M>
Converts to this type from the input type.
Source§impl<M> From<SerialConnection> for Connection<M>where
M: Message,
Available on crate feature direct-serial only.
impl<M> From<SerialConnection> for Connection<M>where
M: Message,
Available on crate feature
direct-serial only.Source§fn from(value: SerialConnection) -> Connection<M>
fn from(value: SerialConnection) -> Connection<M>
Converts to this type from the input type.
Source§impl<M> From<TcpConnection> for Connection<M>where
M: Message,
Available on crate feature tcp only.
impl<M> From<TcpConnection> for Connection<M>where
M: Message,
Available on crate feature
tcp only.Source§fn from(value: TcpConnection) -> Connection<M>
fn from(value: TcpConnection) -> Connection<M>
Converts to this type from the input type.
Source§impl<M> From<UdpConnection> for Connection<M>where
M: Message,
Available on crate feature udp only.
impl<M> From<UdpConnection> for Connection<M>where
M: Message,
Available on crate feature
udp only.Source§fn from(value: UdpConnection) -> Connection<M>
fn from(value: UdpConnection) -> Connection<M>
Converts to this type from the input type.
Source§impl<M> MavConnection<M> for Connection<M>where
M: Message,
impl<M> MavConnection<M> for Connection<M>where
M: Message,
Source§fn recv(&self) -> Result<(MavHeader, M), MessageReadError>
fn recv(&self) -> Result<(MavHeader, M), MessageReadError>
Receive a MAVLink message. Read more
Source§fn recv_raw(&self) -> Result<MAVLinkMessageRaw, MessageReadError>
fn recv_raw(&self) -> Result<MAVLinkMessageRaw, MessageReadError>
Receive a raw, unparsed MAVLink message. Read more
Source§fn try_recv(&self) -> Result<(MavHeader, M), MessageReadError>
fn try_recv(&self) -> Result<(MavHeader, M), MessageReadError>
Try to receive a MAVLink message. Read more
Source§fn send(&self, header: &MavHeader, data: &M) -> Result<usize, MessageWriteError>
fn send(&self, header: &MavHeader, data: &M) -> Result<usize, MessageWriteError>
Send a MAVLink message Read more
Source§fn set_protocol_version(&mut self, version: MavlinkVersion)
fn set_protocol_version(&mut self, version: MavlinkVersion)
Sets the MAVLink version to use for receiving (when
allow_recv_any_version() is false) and sending messages.Source§fn protocol_version(&self) -> MavlinkVersion
fn protocol_version(&self) -> MavlinkVersion
Gets the currently used MAVLink version
Source§fn set_allow_recv_any_version(&mut self, allow: bool)
fn set_allow_recv_any_version(&mut self, allow: bool)
Set wether MAVLink messages of either version may be received. Read more
Source§fn allow_recv_any_version(&self) -> bool
fn allow_recv_any_version(&self) -> bool
Wether messages of any MAVLink version may be received
Source§fn setup_signing(&mut self, signing_data: Option<SigningConfig>)
fn setup_signing(&mut self, signing_data: Option<SigningConfig>)
Available on crate feature
signing only.Setup secret key used for message signing, or disable message signing
Source§fn send_frame(&self, frame: &MavFrame<M>) -> Result<usize, MessageWriteError>
fn send_frame(&self, frame: &MavFrame<M>) -> Result<usize, MessageWriteError>
Write whole frame Read more
Source§fn recv_frame(&self) -> Result<MavFrame<M>, MessageReadError>
fn recv_frame(&self) -> Result<MavFrame<M>, MessageReadError>
Read whole frame Read more
Source§fn send_default(&self, data: &M) -> Result<usize, MessageWriteError>
fn send_default(&self, data: &M) -> Result<usize, MessageWriteError>
Send a message with default header Read more
Auto Trait Implementations§
impl<M> !Freeze for Connection<M>
impl<M> RefUnwindSafe for Connection<M>where
M: RefUnwindSafe,
impl<M> Send for Connection<M>where
M: Send,
impl<M> Sync for Connection<M>where
M: Sync,
impl<M> Unpin for Connection<M>where
M: Unpin,
impl<M> UnwindSafe for Connection<M>where
M: UnwindSafe,
Blanket Implementations§
Source§impl<T> BorrowMut<T> for Twhere
T: ?Sized,
impl<T> BorrowMut<T> for Twhere
T: ?Sized,
Source§fn borrow_mut(&mut self) -> &mut T
fn borrow_mut(&mut self) -> &mut T
Mutably borrows from an owned value. Read more