rosrust

MIT Licensed Crates.io Build Status

rosrust is a pure Rust implementation of a ROS client library.

Implementation

rosrust is under development to implement all features of a ROS Client Library by fulfilling ROS requirements for implementing client libraries which are given in a more detailed form in the technical overview.

Currently implemented features: * ROS Master API, Parameter Server API and most of ROS Slave API (excluding 2 ambiguous methods) * Interface for handling parameters * Publisher, Subscriber, Client, Service fully working (until packet snooping for another undocumented feature is needed) * Simple bindings for messages, but ROS integration for generating them has yet to be done, and will be part of the catkin integration * Manual remapping is provided, and CLI parameter remapping is coming!

There are still quite some features to be implemented for this to become a stable API (for the library user's interface to stop changing). The most important ones are listed as Issues by the repository owner.

Integration with catkin will be handled once a satisfying set of features has been implemented.

Examples

The API is far from being stable, but this is the current desired functionality.

There is a demo project at OTL/rosrust_tutorial, showing everything that needs to be done (including a tiny tiny build.rs script) to get rosrust running.

Most of the examples are followed by an infinite loop. ROS shutdown signal checking is coming!

Messages

Message generation is done at build time. In the build.rs script, all you need to add is:

```rust

[macro_use]

extern crate rosrust; // If you wanted stdmsgs/String, sensormsgs/Imu // and all the message types used by them, like geometrymsgs/Vector3 rosmsgmain!("stdmsgs/String", "sensormsgs/Imu"); ```

You need to depend on rosrust, serde, and serde_derive, and have rosrust as a build dependency. After that, add this to your main file:

```rust

[macro_use]

extern crate rosrust; rosmsg_include!(); ```

This will include all the generated structures, and at them to the msg namespace. Thus, to create a new sensor_msgs/Imu, you call msg::sensor_msgs::Imu::new().

All of the structures implement debug writing, so you can easily inspect their contents.

Publishing to topic

If we wanted to publish a defined message (let's use std_msgs/String) to topic some_topic approximately every second, we can do it in the following way.

```rust extern crate rosrust; use rosrust::Ros; use std::{thread, time};

rosmsg_include!();

fn main() { let mut ros = Ros::new("nodename").unwrap(); let mut publisher = ros.publish("sometopic").unwrap(); loop { thread::sleep(time::Duration::fromsecs(1)); let msg = msg::stdmsgs::String::new(); msg.data = String::from("test"); publisher.send(msg).unwrap(); } } ```

Subscribing to topic

If we wanted to subscribe to an std_msgs/UInt64 topic some_topic, we just declare a callback. An alternative extra interface with iterators is being considered, but for now this is the only option.

```rust extern crate rosrust; use rosrust::Ros; use std::{thread, time};

rosmsg_include!();

fn main() { let mut ros = Ros::new("nodename").unwrap(); ros.subscribe("sometopic", |v: msg::stdmsgs::UInt64| println!("{}", v.data)).unwrap(); loop { thread::sleep(time::Duration::fromsecs(100)); } } ```

Creating a service

Creating a service is the easiest out of all the options. Just define a callback for each request. Let's use some AddTwoInts service on the topic /add_two_ints.

```rust extern crate rosrust; use rosrust::Ros; use std::{thread, time};

rosmsg_include!();

fn main() { let mut ros = Ros::new("nodename").unwrap(); ros.service::("/addtwoints", |req| Ok(msg::ourmsgs::AddTwoIntsRes { sum: req.a + req.b })).unwrap(); loop { thread::sleep(time::Duration::from_secs(100)); } } ```

Creating a client

Clients can handle requests synchronously and asynchronously. The sync method behaves like a function, while the async approach is via reading data afterwards. The async consumes the passed parameter, since we're passing the parameter between threads, and it's more common for users to pass and drop a parameter, so this being the default prevents needless cloning. Let's call requests from the AddTwoInts service on the topic /add_two_ints.

```rust extern crate rosrust; use rosrust::Ros; use std::{thread, time};

fn main() { let ros = Ros::new("nodename").unwrap(); let client = ros.client::("/addtwoints").unwrap(); loop { // Sync approach println!("5 + 7 = {}", client.req(&msg::ourmsgs::AddTwoIntsReq { a: 5, b: 7 }).unwrap().unwrap().sum); // Async approach let retval = client.reqasync(msg::ourmsgs::AddTwoIntsReq { a: 5, b: 7 }); println!("12 + 4 = {}", retval.read().unwrap().unwrap().sum); thread::sleep(time::Duration::from_secs(1)); } } ```

Parameters

```rust extern crate rosrust; use rosrust::Ros;

fn main() { let ros = Ros::new("nodename").unwrap(); let param = ros.param("~cow").unwrap(); // access /nodename/cow parameter println!("Exists? {:?}", param.exists()); // false param.set(&UInt64 { data: 42 }); println!("Get {}", param.get::().unwrap().data); // 42 // XmlRpcValue representing any parameter println!("Get raw {:?}", param.getraw().unwrap()); println!("Search {:?}", param.search().unwrap()); // /nodename/cow println!("Exists? {}", param.exists().unwrap()); // true param.delete().unwrap() println!("Get {:?}", param.get::().unwrap_err()); // fails to find println!("Exists? {}", param.exists()); //false } ```

License

rosrust is distributed under the MIT license.