Struct async_mavlink::AsyncMavConn[][src]

pub struct AsyncMavConn<M: Message> { /* fields omitted */ }

An async adapter for a MAVLink connection

Offers high level functionality to interact with a MAVLink vehicle in an async fashion.

Implementations

impl<M: 'static + Message + Clone + Send + Sync> AsyncMavConn<M>[src]

pub fn new(
    address: &str,
    mavlink_version: MavlinkVersion
) -> Result<(Arc<Self>, impl Future<Output = impl Send> + Send), AsyncMavlinkError>
[src]

Construct a new MavlinkConnectionHandler

Arguments

  • address - MAVLink connection &str. Equivalent to the address argument in mavlink::connect

Examples

use async_mavlink::prelude::*;
use mavlink::{MavlinkVersion, common::MavMessage};
use smol::prelude::*;

smol::block_on(async {
    let (conn, future) = AsyncMavConn::new("udpbcast:127.0.0.2:14551", MavlinkVersion::V1)?;
    smol::spawn(async move { future.await }).detach();
    // ...
})

pub async fn subscribe(
    &self,
    message_type: MavMessageType<M>
) -> Result<Pin<Box<dyn Stream<Item = M>>>, AsyncMavlinkError>
[src]

Subscribe to all new MavMessages of the given MavMessageType

This returns a never-ending Stream of MavMessages.

Arguments

  • message_type - MavMessageType of the desired messages

Examples

let message_type = MavMessageType::new(&MavMessage::PARAM_VALUE(Default::default()));
let mut stream = conn.subscribe(message_type).await?;
while let Some(MavMessage::PARAM_VALUE(data)) = (stream.next()).await {
    // do something with `data`
}

pub async fn request(&self, message_type: MavMessageType<M>) -> M[src]

Awaits the next MavMessage of the given MavMessageType

Arguments

  • message_type - MavMessageType of the desired messages

Examples

let message_type = MavMessageType::new(&MavMessage::PARAM_VALUE(Default::default()));

if let MavMessage::PARAM_VALUE(data) = conn.request(message_type).await {
    // do something with `data`
}

pub async fn send(
    &self,
    header: &MavHeader,
    message: &M
) -> Result<(), AsyncMavlinkError>
[src]

Send a MavMessage to the vehicle

Arguments

  • message - MavMessage to send

Examples

let header = MavHeader::default();
let message = MavMessage::PARAM_REQUEST_LIST(PARAM_REQUEST_LIST_DATA {
    target_component: 0,
    target_system: 0,
});

conn.send(&header, &message).await?;

pub async fn send_default(&self, message: &M) -> Result<(), AsyncMavlinkError>[src]

Send a MavMessage to the vehicle

Arguments

  • message - MavMessage to send

Examples

let message = MavMessage::PARAM_REQUEST_LIST(PARAM_REQUEST_LIST_DATA {
    target_component: 0,
    target_system: 0,
});

conn.send_default(&message).await?;

pub async fn last_heartbeat(&self) -> Option<Instant>[src]

Returns the Instant from the last received HEARTBEAT

Auto Trait Implementations

impl<M> !RefUnwindSafe for AsyncMavConn<M>[src]

impl<M> Send for AsyncMavConn<M> where
    M: Send
[src]

impl<M> Sync for AsyncMavConn<M> where
    M: Send
[src]

impl<M> Unpin for AsyncMavConn<M>[src]

impl<M> !UnwindSafe for AsyncMavConn<M>[src]

Blanket Implementations

impl<T> Any for T where
    T: 'static + ?Sized
[src]

impl<T> Borrow<T> for T where
    T: ?Sized
[src]

impl<T> BorrowMut<T> for T where
    T: ?Sized
[src]

impl<T> From<T> for T[src]

impl<T, U> Into<U> for T where
    U: From<T>, 
[src]

impl<T, U> TryFrom<U> for T where
    U: Into<T>, 
[src]

type Error = Infallible

The type returned in the event of a conversion error.

impl<T, U> TryInto<U> for T where
    U: TryFrom<T>, 
[src]

type Error = <U as TryFrom<T>>::Error

The type returned in the event of a conversion error.