29个版本

0.9.11 2023年4月1日
0.9.10 2022年4月15日
0.9.8 2021年8月23日
0.9.6 2021年3月13日
0.2.0 2016年7月18日

#18 in 机器人

Download history 377/week @ 2024-04-22 239/week @ 2024-04-29 315/week @ 2024-05-06 397/week @ 2024-05-13 254/week @ 2024-05-20 295/week @ 2024-05-27 266/week @ 2024-06-03 275/week @ 2024-06-10 242/week @ 2024-06-17 285/week @ 2024-06-24 244/week @ 2024-07-01 288/week @ 2024-07-08 256/week @ 2024-07-15 261/week @ 2024-07-22 411/week @ 2024-07-29 235/week @ 2024-08-05

1,185 每月下载量
用于 12 个包(10个直接使用)

MIT 许可

320KB
8K SLoC

rosrust

MIT Licensed Crates.io Build Status

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/PointCloud2sensor_msgs/Image 编码/解码、TF树处理以及其他在 roscpprospy 中也是外部库的东西。

API非常接近最终的样式。

一旦实现了令人满意的功能集,将处理与 catkin 的集成。

示例

API即将达到其最终形式。

示例文件夹 中有多个示例。发布者/订阅者和服务/客户端示例被设计成尽可能模仿 roscpp 教程。

功能

消息生成

可以通过依赖 rosrust_msg 自动生成消息,或者使用 rosrust::rosmsg_include 手动生成。

首选方法是自动的,因为它允许消息使用依赖项与您的包之间的互操作。

如果您没有安装ROS,则消息生成将使用环境变量ROSRUST_MSG_PATH,这是一个以冒号分隔的目录列表,用于搜索。这些目录应该具有以下结构:<ROSRUST_MSG_PATH>/<anything>/<package>/msg/<message><ROSRUST_MSG_PATH>/<anything>/<package>/srv/<service>

自动

对于自动消息生成,只需依赖rosrust_msg即可,版本信息见本文件顶部。

之后,您可以使用以下方式生成一个sensor_msgs/Imu消息对象:rosrust_msg::sensor_msgs::Imu::default()。所有字段始终是公共的,因此您可以像初始化文本字面量一样初始化结构。

手动

消息生成是在构建时完成的。如果您已安装ROS并在shell会话中已源码,则无需为此进行任何额外设置。

要生成消息,创建一个消息模块。例如,在项目根目录下使用一个msg.rs文件,结果类似于导入roscpprospy。该文件只需要一行

// 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()。所有字段始终是公共的,因此您可以像初始化文本字面量一样初始化结构。

发布到主题

如果我们想要每秒发布10次一个定义的消息(让我们使用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消耗传递的参数,因为我们是在线程之间传递参数。用户通常传递和丢弃参数,所以这是默认的,可以防止不必要的克隆。

让我们将主题 /add_two_ints 上对 AddTwoInts 服务的请求称为。这些数字应作为命令行参数提供。

此外,我们还需要依赖 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!() 来提供。

还有节流日志选项可用。

命令行重映射

rospyroscpp 类似,您可以使用命令行来重映射主题和私有参数。私有参数应以 YAML 格式提供。

有关更多信息,请参阅官方维基百科,因为目标是100%模仿此接口。

您可以使用 rosrust::args() 获取剩余的命令行参数字符串的向量,这允许轻松解析参数。这包括第一个参数,应用程序名称。

许可证

rosrust 在 MIT 许可证下分发。

依赖关系

~24–36MB
~776K SLoC