Trait mavlink::MavConnection [−][src]
pub trait MavConnection<M: Message> {
fn recv(&self) -> Result<(MavHeader, M), MessageReadError>;
fn send(
&self,
header: &MavHeader,
data: &M
) -> Result<usize, MessageWriteError>;
fn set_protocol_version(&mut self, version: MavlinkVersion);
fn get_protocol_version(&self) -> MavlinkVersion;
fn send_frame(
&self,
frame: &MavFrame<M>
) -> Result<usize, MessageWriteError> { ... }
fn recv_frame(&self) -> Result<MavFrame<M>, MessageReadError> { ... }
fn send_default(&self, data: &M) -> Result<usize, MessageWriteError> { ... }
}
Expand description
A MAVLink connection
Required methods
Receive a mavlink message.
Blocks until a valid frame is received, ignoring invalid messages.
Send a mavlink message
fn set_protocol_version(&mut self, version: MavlinkVersion)
fn get_protocol_version(&self) -> MavlinkVersion
Provided methods
fn send_frame(&self, frame: &MavFrame<M>) -> Result<usize, MessageWriteError>
fn send_frame(&self, frame: &MavFrame<M>) -> Result<usize, MessageWriteError>
Write whole frame
fn recv_frame(&self) -> Result<MavFrame<M>, MessageReadError>
fn recv_frame(&self) -> Result<MavFrame<M>, MessageReadError>
Read whole frame
fn send_default(&self, data: &M) -> Result<usize, MessageWriteError>
fn send_default(&self, data: &M) -> Result<usize, MessageWriteError>
Send a message with default header