pub struct AsyncMavConn<M: Message> { /* private fields */ }
Expand description
An async adapter for a MAVLink connection
Offers high level functionality to interact with a MAVLink vehicle in an async fashion.
Implementations§
Source§impl<M: 'static + Message + Clone + Send + Sync> AsyncMavConn<M>
impl<M: 'static + Message + Clone + Send + Sync> AsyncMavConn<M>
Sourcepub fn new(
address: &str,
mavlink_version: MavlinkVersion,
) -> Result<(Arc<Self>, impl Future<Output = impl Send> + Send), AsyncMavlinkError>
pub fn new( address: &str, mavlink_version: MavlinkVersion, ) -> Result<(Arc<Self>, impl Future<Output = impl Send> + Send), AsyncMavlinkError>
Construct a new MavlinkConnectionHandler
§Arguments
address
- MAVLink connection&str
. Equivalent to theaddress
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();
// ...
})
Sourcepub async fn subscribe(
&self,
message_type: MavMessageType<M>,
) -> Result<Pin<Box<dyn Stream<Item = M>>>, AsyncMavlinkError>
pub async fn subscribe( &self, message_type: MavMessageType<M>, ) -> Result<Pin<Box<dyn Stream<Item = M>>>, AsyncMavlinkError>
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`
}
Sourcepub async fn request(&self, message_type: MavMessageType<M>) -> M
pub async fn request(&self, message_type: MavMessageType<M>) -> M
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`
}
Sourcepub async fn send_default(&self, message: &M) -> Result<(), AsyncMavlinkError>
pub async fn send_default(&self, message: &M) -> Result<(), AsyncMavlinkError>
Sourcepub async fn last_heartbeat(&self) -> Option<Instant>
pub async fn last_heartbeat(&self) -> Option<Instant>
Returns the Instant
from the last received HEARTBEAT
Auto Trait Implementations§
impl<M> Freeze for AsyncMavConn<M>
impl<M> !RefUnwindSafe for AsyncMavConn<M>
impl<M> Send for AsyncMavConn<M>where
M: Send,
impl<M> Sync for AsyncMavConn<M>where
M: Send,
impl<M> Unpin for AsyncMavConn<M>
impl<M> !UnwindSafe for AsyncMavConn<M>
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