4 个版本
0.1.3 | 2021 年 2 月 2 日 |
---|---|
0.1.2 | 2021 年 2 月 2 日 |
0.1.1 | 2020 年 9 月 29 日 |
0.1.0 | 2020 年 9 月 28 日 |
在 机器人 类别中排名 #179
每月下载量 35
26KB
300 行
async-mavlink
异步适配器,用于 mavlink crate
mavlink crate 提供了 MAVLink 连接的低级 API。此 crate 在其之上添加了一个薄薄的异步 API。最重要的功能是基于订阅的通信模型。它允许用户订阅某种类型的信息。所有后续的该类型信息都可以在异步流中接收。为了使其功能正常,需要将连接器的事件循环作为任务执行。此 crate 的目标是执行器无关,例如,它应该与所有异步执行器一起工作。
到目前为止,这只是一个概念证明。虽然它可能很好地满足您的用例,但请预期某些事情可能会出错。欢迎贡献和建议!
示例:从车辆中拉取所有参数
在此示例中,利用订阅方法收集车辆的所有参数。
use std::collections::HashMap;
use async_mavlink::prelude::*;
use mavlink::{MavlinkVersion, common::*};
use smol::prelude::*;
smol::block_on(async {
// connect
let (conn, future) = AsyncMavConn::new("udpin:127.0.0.1:14551", MavlinkVersion::V1)?;
// start event loop
smol::spawn(async move { future.await }).detach();
// we want to subscribe to PARAM_VALUE messages
let msg_type = MavMessageType::new(&MavMessage::PARAM_VALUE(Default::default()));
// subscribe to PARAM_VALUE message
let mut stream = conn.subscribe(msg_type).await?;
// and send one PARAM_REQUEST_LIST message
let msg_request = MavMessage::PARAM_REQUEST_LIST(Default::default());
conn.send_default(&msg_request).await?;
let mut parameters = HashMap::new();
// receive all parameters and store them in a HashMap
while let Some(MavMessage::PARAM_VALUE(data)) = (stream.next()).await {
parameters.insert(to_string(&data.param_id), data.param_value);
if data.param_count as usize == parameters.len(){
break;
}
}
// do something with parameters
})
许可:MIT OR Apache-2.0
依赖项
~4MB
~74K SLoC