pub trait MavConnection<M: Message> {
    // Required methods
    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;

    // Provided methods
    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§

source

fn recv(&self) -> Result<(MavHeader, M), MessageReadError>

Receive a mavlink message.

Blocks until a valid frame is received, ignoring invalid messages.

source

fn send(&self, header: &MavHeader, data: &M) -> Result<usize, MessageWriteError>

Send a mavlink message

source

fn set_protocol_version(&mut self, version: MavlinkVersion)

source

fn get_protocol_version(&self) -> MavlinkVersion

Provided Methods§

source

fn send_frame(&self, frame: &MavFrame<M>) -> Result<usize, MessageWriteError>

Write whole frame

source

fn recv_frame(&self) -> Result<MavFrame<M>, MessageReadError>

Read whole frame

source

fn send_default(&self, data: &M) -> Result<usize, MessageWriteError>

Send a message with default header

Implementors§