8 个版本
0.1.7 | 2023年4月1日 |
---|---|
0.1.6 | 2022年4月15日 |
0.1.4 | 2021年8月23日 |
0.1.2 | 2021年3月13日 |
0.1.0 | 2020年2月14日 |
在 机器人 类别中排名第57
每月下载量 809
在 3 个库 中使用
225KB
5.5K SLoC
rosrust
rosrust 是一个纯 Rust 实现的 ROS 客户端库。
用法
对于所有主要功能,仅依赖库本身就足够了。强烈建议同时依赖 rosrust_msg
,因为它提供了消息生成的绑定。
以下是一些推荐使用的依赖项以使用此库
[dependencies]
rosrust = "0.9"
rosrust_msg = "0.1"
如果使用 Rust 2015 版本,只需使用宏依赖库即可,使用
#[macro_use]
extern crate rosrust;
示例使用 Rust 2018 版本编写,因为现在是预期使用的版本。
实现
rosrust 通过满足 ROS 实现客户端库的要求(这些要求在 技术概述 中以更详细的形式给出)来几乎实现了 ROS 客户端库的所有功能。
大多数缺失的功能都与额外的工具有关,如 sensor_msgs/PointCloud2
和 sensor_msgs/Image
编码/解码,TF 树处理,以及在其他库(如 roscpp
和 rospy
)中也是外部库的其他事情。
API 非常接近最终的形式。
一旦实现了一组令人满意的功能,将处理与 catkin 的集成。
示例
API 几乎达到了最终形式。
在 示例文件夹 中有多个示例。发布/订阅和客户端/服务示例被设计成尽可能模仿 roscpp
教程。
功能
消息生成
可以通过依赖 rosrust_msg
自动执行消息生成,或者使用 rosrust::rosmsg_include
手动进行。
首选的方法是自动的,因为它允许消息和你的crate之间进行互操作性。
如果你没有安装ROS,那么消息生成将使用环境变量ROSRUST_MSG_PATH
,这是一个冒号分隔的目录列表,用于搜索。这些目录应具有以下结构:<ROSRUST_MSG_PATH>/<anything>/<package>/msg/<message>
或<ROSRUST_MSG_PATH>/<anything>/<package>/srv/<service>
。
自动
对于自动消息生成,只需依赖rosrust_msg
,版本在本文档顶部指定。
之后,你可以通过使用rosrust_msg::sensor_msgs::Imu::default()
来生成一个sensor_msgs/Imu
消息对象。所有字段始终是公开的,所以你可以用字面量初始化结构。
手动
消息生成在构建时完成。如果你已安装ROS并在shell会话中源了它,则不需要为此进行任何额外设置。
要生成消息,为消息创建一个模块。在你的项目根目录中使用类似于msg.rs
的文件,会导致导入类似于roscpp
和rospy
。该文件只需要一行。
// If you wanted
// * messages: std_msgs/String, sensor_msgs/Imu
// * services: roscpp_tutorials/TwoInts
// * and all the message types used by them, like geometry_msgs/Vector3
rosrust::rosmsg_include!(std_msgs/String,sensor_msgs/Imu,roscpp_tutorials/TwoInts);
只需将此文件添加到你的项目中,你就完成了。
如果你将其放在src/msg.rs
文件中,这将包含所有生成的结构,并将它们添加到msg
命名空间中。因此,要创建一个新的sensor_msgs/Imu
,你调用msg::sensor_msgs::Imu::default()
。所有字段始终是公开的,所以你可以用字面量初始化结构。
发布到主题
如果我们想每秒将定义的消息(让我们使用std_msgs/String
)发布到chatter
主题,我们可以这样做。
fn main() {
// Initialize node
rosrust::init("talker");
// Create publisher
let chatter_pub = rosrust::publish("chatter", 100).unwrap();
let mut count = 0;
// Create object that maintains 10Hz between sleep requests
let rate = rosrust::rate(10.0);
// Breaks when a shutdown signal is sent
while rosrust::is_ok() {
// Create string message
let mut msg = rosrust_msg::std_msgs::String::default();
msg.data = format!("hello world {}", count);
// Send string message to topic via publisher
chatter_pub.send(msg).unwrap();
// Sleep to maintain 10Hz rate
rate.sleep();
count += 1;
}
}
订阅到主题
如果我们想订阅一个std_msgs/UInt64
主题some_topic
,我们只需声明一个回调。目前正在考虑一个带有迭代器的额外接口,但现在这只有一个选项。
构造函数创建一个对象,表示订阅者的生命周期。在此对象销毁时,主题也会取消订阅。
fn main() {
// Initialize node
rosrust::init("listener");
// Create subscriber
// The subscriber is stopped when the returned object is destroyed
let _subscriber_raii = rosrust::subscribe("chatter", 100, |v: rosrust_msg::std_msgs::UInt64| {
// Callback for handling received messages
rosrust::ros_info!("Received: {}", v.data);
}).unwrap();
// Block the thread until a shutdown signal is received
rosrust::spin();
}
创建服务
创建服务是最简单的方法。只需为每个请求定义一个回调。让我们使用位于/add_two_ints
主题上的roscpp_tutorials/AddTwoInts
服务。
fn main() {
// Initialize node
rosrust::init("add_two_ints_server");
// Create service
// The service is stopped when the returned object is destroyed
let _service_raii =
rosrust::service::<rosrust_msg::roscpp_tutorials::TwoInts, _>("add_two_ints", move |req| {
// Callback for handling requests
let sum = req.a + req.b;
// Log each request
rosrust::ros_info!("{} + {} = {}", req.a, req.b, sum);
Ok(rosrust_msg::roscpp_tutorials::TwoIntsRes { sum })
}).unwrap();
// Block the thread until a shutdown signal is received
rosrust::spin();
}
创建客户端
客户端可以同步和异步地处理请求。sync方法的行为像一个函数,而async方法则是通过后续读取数据。async消耗传递的参数,因为我们是在线程之间传递参数。用户通常传递和丢弃参数,所以这是默认的,以防止不必要的克隆。
让我们称来自 AddTwoInts
服务、主题 /add_two_ints
的请求。数字应以命令行参数的形式提供。
我们还在这里依赖 env_logger
来将 ros_info
消息记录到标准输出。
use std::{env, time};
fn main() {
env_logger::init();
// Fetch args that are not meant for rosrust
let args: Vec<_> = rosrust::args();
if args.len() != 3 {
eprintln!("usage: client X Y");
return;
}
let a = args[1].parse::<i64>().unwrap();
let b = args[2].parse::<i64>().unwrap();
// Initialize node
rosrust::init("add_two_ints_client");
// Wait ten seconds for the service to appear
rosrust::wait_for_service("add_two_ints", Some(time::Duration::from_secs(10))).unwrap();
// Create client for the service
let client = rosrust::client::<rosrust_msg::roscpp_tutorials::TwoInts>("add_two_ints").unwrap();
// Synchronous call that blocks the thread until a response is received
ros_info!(
"{} + {} = {}",
a,
b,
client
.req(&rosrust_msg::roscpp_tutorials::TwoIntsReq { a, b })
.unwrap()
.unwrap()
.sum
);
// Asynchronous call that can be resolved later on
let retval = client.req_async(rosrust_msg::roscpp_tutorials::TwoIntsReq { a, b });
rosrust::ros_info!("{} + {} = {}", a, b, retval.read().unwrap().unwrap().sum);
}
参数
提供了很多方法,所以我们在这里仅展示其中一些。获取请求返回结果,因此您可以使用 unwrap_or
来处理默认值。
我们还在这里依赖 env_logger
来将 ros_info
消息记录到标准输出。
fn main() {
env_logger::init();
// Initialize node
rosrust::init("param_test");
// Create parameter, go through all methods, and delete it
let param = rosrust::param("~foo").unwrap();
rosrust::ros_info!("Handling ~foo:");
rosrust::ros_info!("Exists? {:?}", param.exists()); // false
param.set(&42u64).unwrap();
rosrust::ros_info!("Get: {:?}", param.get::<u64>().unwrap());
rosrust::ros_info!("Get raw: {:?}", param.get_raw().unwrap());
rosrust::ros_info!("Search: {:?}", param.search().unwrap());
rosrust::ros_info!("Exists? {}", param.exists().unwrap());
param.delete().unwrap();
rosrust::ros_info!("Get {:?}", param.get::<u64>().unwrap_err());
rosrust::ros_info!("Get with default: {:?}", param.get::<u64>().unwrap_or(44u64));
rosrust::ros_info!("Exists? {}", param.exists().unwrap());
}
日志记录
日志记录通过宏 ros_debug!()
、ros_info!()
、ros_warn!()
、ros_error!()
、ros_fatal!()
提供。
还提供了节流日志选项。
命令行重映射
类似于 rospy
和 roscpp
,您可以使用命令行来重映射主题和私有参数。私有参数应以 YAML 格式提供。
有关更多信息,请参阅 官方维基百科,因为目标是100%模仿此接口。
您可以使用 rosrust::args()
获取剩余的命令行参数字符串向量,允许轻松解析参数。这包括第一个参数,应用程序名称。
许可证
rosrust 在 MIT 许可证下分发。
依赖关系
~24–36MB
~780K SLoC