[][src]Trait mavlink::MavConnection

pub trait MavConnection<M: Message> {
    fn recv(&self) -> Result<(MavHeader, M), MessageReadError>;
fn send(&self, header: &MavHeader, data: &M) -> Result<()>;
fn set_protocol_version(&mut self, version: MavlinkVersion);
fn get_protocol_version(&self) -> MavlinkVersion; fn send_frame(&self, frame: &MavFrame<M>) -> Result<()> { ... }
fn recv_frame(&self) -> Result<MavFrame<M>, MessageReadError> { ... }
fn send_default(&self, data: &M) -> Result<()> { ... } }

A MAVLink connection

Required methods

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

Receive a mavlink message.

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

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

Send a mavlink message

fn set_protocol_version(&mut self, version: MavlinkVersion)

fn get_protocol_version(&self) -> MavlinkVersion

Loading content...

Provided methods

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

Write whole frame

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

Read whole frame

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

Send a message with default header

Loading content...

Implementors

Loading content...