Document all the things.

This commit is contained in:
Martin Dahl 2021-09-01 23:18:06 +02:00
parent 807d9fc59b
commit a2c4339f58
19 changed files with 343 additions and 106 deletions

View File

@ -1,13 +1,15 @@
R2R - Minimal ROS2 Rust bindings
R2R - Easy to use, runtime-agnostic, async rust bindings for ROS2.
====================
Minimal bindings for ROS2 that do *not* require hooking in to the ROS2 build infrastructure -- `cargo build` is all you need. Convenience Rust types are created by calling into the c introspection libraries. This circumvents the ROS2 .msg/.idl pipeline by relying on already generated C code. The convenience types can be ignored when you need to trade convenience for performance, e.g. treating large chunks of data manually. By default, the behavior is to build bindings to the RCL and all message types that can be found in the currently sourced ros environment.
Easy to use bindings for ROS2 that do *not* require hooking in to the ROS2 build infrastructure -- `cargo build` is all you need. Convenience Rust types are created by calling into the c introspection libraries. This circumvents the ROS2 .msg/.idl pipeline by relying on already generated C code. By default, the behavior is to build bindings to the RCL and all message types that can be found in the currently sourced ros environment.
When integration with the colcon build system is desired, a CMakeLists.txt file can be used to limit the generation of bindings to only include specific (idl) dependencies. This is done through additional environment variables. A minimal example of the colcon integration is available here: <https://github.com/m-dahl/r2r_minimal_node/>.
This library differ a bit in style from rclpy and rclcpp as it eliminates all synchronous callbacks in favor of rust futures and streams. Coupled with the rust await syntax, this makes it very pleasant to work with ROS services and actions. The library purposefully does not chose an async runtime -- this means that the user needs to take care of any task spawning. This also limits the API to what futures-rs provides.
Manual is available on github pages <https://sequenceplanner.github.io/r2r/> (documention is lacking though).
These bindings are being written organically when things are needed by me and others so please be aware that the API will change.
These bindings are being written organically when things are needed by me and others so please be aware that the API will change. As of now I have no intention of wrapping all of the RCL just for the sake of completeness.
How to use
--------------------
@ -33,11 +35,11 @@ What works?
- Publish/subscribe
- Services
- Actions
- Static parameters (e.g. loading from yaml files and parsing launch parameters)
- Rudimentary parameter handling
TODO
--------------------
- Implement the services associated with updating parameters at run-time.
- Complete the services associated with updating parameters at run-time.
- Documentation. (For now, look at the examples.)
- General cleanup and error handling.
- Expose more of the RCL like QoS settings.

View File

@ -9,7 +9,7 @@ use std::sync::{Arc, Mutex};
// main goal handling routine.
async fn run_goal(
node: Arc<Mutex<r2r::Node>>,
g: r2r::ServerGoal<Fibonacci::Action>,
g: r2r::ActionServerGoal<Fibonacci::Action>,
) -> Fibonacci::Result {
let mut timer = node // local timer, will be dropped after this request is processed.
.lock()
@ -40,7 +40,7 @@ async fn run_goal(
async fn fibonacci_server(
spawner: LocalSpawner,
node: Arc<Mutex<r2r::Node>>,
mut requests: impl Stream<Item = r2r::GoalRequest<Fibonacci::Action>> + Unpin,
mut requests: impl Stream<Item = r2r::ActionServerGoalRequest<Fibonacci::Action>> + Unpin,
) {
loop {
match requests.next().await {

View File

@ -5,7 +5,7 @@ use r2r;
async fn requester_task(
node_available: impl Future<Output = r2r::Result<()>>,
c: r2r::UntypedClient,
c: r2r::ClientUntyped,
) -> Result<(), Box<dyn std::error::Error>> {
let mut x: i64 = 0;
println!("waiting for service...");

View File

@ -1,8 +1,8 @@
use futures::executor::LocalPool;
use futures::task::LocalSpawnExt;
use std::rc::Rc;
use std::cell::RefCell;
use r2r;
use std::cell::RefCell;
use std::rc::Rc;
async fn timer_task(mut t: r2r::Timer) -> Result<(), Box<dyn std::error::Error>> {
let mut x: i32 = 0;
@ -39,7 +39,7 @@ fn main() -> Result<(), Box<dyn std::error::Error>> {
Ok(()) => {
*task_is_done.borrow_mut() = true;
println!("exiting");
},
}
Err(e) => println!("error: {}", e),
}
})?;

View File

@ -1,7 +1,19 @@
use futures::channel::{mpsc, oneshot};
use futures::future::{FutureExt, TryFutureExt};
use futures::stream::Stream;
use std::collections::HashMap;
use std::future::Future;
use std::sync::{Mutex, Weak};
use std::mem::MaybeUninit;
use std::ffi::CString;
use super::*;
unsafe impl<T> Send for ActionClient<T> where T: WrappedActionTypeSupport {}
/// Action client
///
/// Use this to make goal requests to an action server.
#[derive(Clone)]
pub struct ActionClient<T>
where
@ -10,10 +22,13 @@ where
client: Weak<Mutex<WrappedActionClient<T>>>,
}
unsafe impl<T> Send for ClientGoal<T> where T: WrappedActionTypeSupport {}
unsafe impl<T> Send for ActionClientGoal<T> where T: WrappedActionTypeSupport {}
/// Action client goal handle
///
/// This can be used to cancel goals and query the status of goals.
#[derive(Clone)]
pub struct ClientGoal<T>
pub struct ActionClientGoal<T>
where
T: WrappedActionTypeSupport,
{
@ -21,10 +36,11 @@ where
pub uuid: uuid::Uuid,
}
impl<T: 'static> ClientGoal<T>
impl<T: 'static> ActionClientGoal<T>
where
T: WrappedActionTypeSupport,
{
/// Get the current status of this goal.
pub fn get_status(&self) -> Result<GoalStatus> {
let client = self
.client
@ -35,6 +51,13 @@ where
Ok(client.get_goal_status(&self.uuid))
}
/// Send a cancel request for this goal to the server.
///
/// If the server accepts and completes the request, the future completes without error.
/// Otherwise, one of these errors can be returned:
/// - `GoalCancelRejected`
/// - `GoalCancelUnknownGoalID`
/// - `GoalCancelAlreadyTerminated`
pub fn cancel(&self) -> Result<impl Future<Output = Result<()>>> {
// upgrade to actual ref. if still alive
let client = self
@ -51,13 +74,19 @@ impl<T: 'static> ActionClient<T>
where
T: WrappedActionTypeSupport,
{
/// Make a new goal request.
///
/// If the server accepts the new goal, the future resolves to a triple of:
/// - A goal handle.
/// - A new future for the eventual result.
/// - A stream of feedback messages.
pub fn send_goal_request(
&self,
goal: T::Goal,
) -> Result<
impl Future<
Output = Result<(
ClientGoal<T>,
ActionClientGoal<T>,
impl Future<Output = Result<(GoalStatus, T::Result)>>,
impl Stream<Item = T::Feedback> + Unpin,
)>,
@ -115,7 +144,7 @@ where
}
Ok((
ClientGoal {
ActionClientGoal {
client: fut_client,
uuid,
},
@ -143,6 +172,7 @@ where
ActionClient { client }
}
/// The status of a goal.
#[derive(Debug, Copy, Clone, PartialEq)]
pub enum GoalStatus {
Unknown,

View File

@ -1,25 +1,41 @@
use futures::channel::{mpsc, oneshot};
use futures::future::{FutureExt, TryFutureExt};
use futures::stream::Stream;
use std::collections::HashMap;
use std::future::Future;
use std::sync::{Mutex, Weak};
use std::mem::MaybeUninit;
use super::*;
//
// TODO: refactor this to separate out shared code between action client and this.
// TODO: refactor this to separate out shared code between typed action client and this.
//
unsafe impl Send for ActionClientUntyped {}
/// Action client (untyped)
///
/// Use this to make goal requests to an action server, without having
/// the concrete types at compile-time.
#[derive(Clone)]
pub struct ActionClientUntyped {
client: Weak<Mutex<WrappedActionClientUntyped>>,
}
unsafe impl Send for ClientGoalUntyped {}
unsafe impl Send for ActionClientGoalUntyped {}
/// Action client goal handle (untyped)
///
/// This can be used to cancel goals and query the status of goals.
#[derive(Clone)]
pub struct ClientGoalUntyped {
pub struct ActionClientGoalUntyped {
client: Weak<Mutex<WrappedActionClientUntyped>>,
pub uuid: uuid::Uuid,
}
impl ClientGoalUntyped {
impl ActionClientGoalUntyped {
/// Get the current status of this goal.
pub fn get_status(&self) -> Result<GoalStatus> {
let client = self
.client
@ -30,6 +46,13 @@ impl ClientGoalUntyped {
Ok(client.get_goal_status(&self.uuid))
}
/// Send a cancel request for this goal to the server.
///
/// If the server accepts and completes the request, the future completes without error.
/// Otherwise, one of these errors can be returned:
/// - `GoalCancelRejected`
/// - `GoalCancelUnknownGoalID`
/// - `GoalCancelAlreadyTerminated`
pub fn cancel(&self) -> Result<impl Future<Output = Result<()>>> {
// upgrade to actual ref. if still alive
let client = self
@ -43,13 +66,19 @@ impl ClientGoalUntyped {
}
impl ActionClientUntyped {
/// Make a new goal request.
///
/// If the server accepts the new goal, the future resolves to a triple of:
/// - A goal handle.
/// - A new future for the eventual result. (as `serde_json::Value`)
/// - A stream of feedback messages. (as `serde_json::Value`)
pub fn send_goal_request(
&self,
goal: serde_json::Value, // T::Goal
) -> Result<
impl Future<
Output = Result<(
ClientGoalUntyped,
ActionClientGoalUntyped,
impl Future<Output = Result<(GoalStatus, Result<serde_json::Value>)>>, // T::Result
impl Stream<Item = Result<serde_json::Value>> + Unpin, // T::Feedback
)>,
@ -104,7 +133,7 @@ impl ActionClientUntyped {
}
Ok((
ClientGoalUntyped {
ActionClientGoalUntyped {
client: fut_client,
uuid,
},

View File

@ -1,29 +1,14 @@
use super::*;
use futures::channel::{mpsc, oneshot};
use futures::future::FutureExt;
use futures::future::{join_all, JoinAll};
use futures::stream::Stream;
use retain_mut::RetainMut;
use std::collections::HashMap;
use std::ffi::CString;
use std::mem::MaybeUninit;
use std::sync::{Arc, Mutex, Weak};
#[derive(Clone)]
pub struct ActionServer<T>
where
T: WrappedActionTypeSupport,
{
server: Weak<Mutex<WrappedActionServer<T>>>,
}
impl<T> ActionServer<T>
where
T: WrappedActionTypeSupport,
{
pub fn is_valid(&self) -> Result<bool> {
// upgrade to actual ref. if still alive
let action_server = self
.server
.upgrade()
.ok_or(Error::RCL_RET_ACTION_SERVER_INVALID)?;
let action_server = action_server.lock().unwrap();
Ok(unsafe { rcl_action_server_is_valid(&action_server.rcl_handle) })
}
}
use super::*;
pub trait ActionServer_ {
fn handle(&self) -> &rcl_action_server_t;
@ -50,12 +35,13 @@ pub trait ActionServer_ {
fn destroy(&mut self, node: &mut rcl_node_t);
}
pub struct CancelRequest {
/// Request to cancel an active goal.
pub struct ActionServerCancelRequest {
pub uuid: uuid::Uuid,
response_sender: oneshot::Sender<(uuid::Uuid, bool)>,
}
impl CancelRequest {
impl ActionServerCancelRequest {
/// Accepts the cancel request. The action server should now cancel the corresponding goal.
pub fn accept(self) {
match self.response_sender.send((self.uuid, true)) {
@ -72,26 +58,32 @@ impl CancelRequest {
}
}
pub struct GoalRequest<T>
/// Request to the action server to accept a new `Goal`.
pub struct ActionServerGoalRequest<T>
where
T: WrappedActionTypeSupport,
{
pub uuid: uuid::Uuid,
pub goal: T::Goal,
cancel_requests: mpsc::Receiver<CancelRequest>,
cancel_requests: mpsc::Receiver<ActionServerCancelRequest>,
server: Weak<Mutex<dyn ActionServer_>>,
request_id: rmw_request_id_t,
}
unsafe impl<T> Send for GoalRequest<T> where T: WrappedActionTypeSupport {}
unsafe impl<T> Send for ActionServerGoalRequest<T> where T: WrappedActionTypeSupport {}
impl<T: 'static> GoalRequest<T>
impl<T: 'static> ActionServerGoalRequest<T>
where
T: WrappedActionTypeSupport,
{
/// Accept the goal request and become a ServerGoal.
/// Returns a handle to the goal and a stream on which cancel requests can be received.
pub fn accept(mut self) -> Result<(ServerGoal<T>, impl Stream<Item = CancelRequest> + Unpin)> {
pub fn accept(
mut self,
) -> Result<(
ActionServerGoal<T>,
impl Stream<Item = ActionServerCancelRequest> + Unpin,
)> {
let uuid_msg = unique_identifier_msgs::msg::UUID {
uuid: self.uuid.as_bytes().to_vec(),
};
@ -131,7 +123,7 @@ where
server.publish_status();
let g = ServerGoal {
let g = ActionServerGoal {
uuid: self.uuid.clone(),
goal: self.goal,
server: self.server,
@ -175,8 +167,8 @@ where
{
pub rcl_handle: rcl_action_server_t,
pub clock_handle: Box<rcl_clock_t>,
pub goal_request_sender: mpsc::Sender<GoalRequest<T>>,
pub cancel_senders: HashMap<uuid::Uuid, mpsc::Sender<CancelRequest>>,
pub goal_request_sender: mpsc::Sender<ActionServerGoalRequest<T>>,
pub cancel_senders: HashMap<uuid::Uuid, mpsc::Sender<ActionServerCancelRequest>>,
pub active_cancel_requests: Vec<(
rmw_request_id_t,
action_msgs::srv::CancelGoal::Response,
@ -363,10 +355,10 @@ where
let (uuid_msg, goal) = T::destructure_goal_request_msg(msg);
let uuid = uuid::Uuid::from_bytes(vec_to_uuid_bytes(uuid_msg.uuid.clone()));
let (cancel_sender, cancel_receiver) = mpsc::channel::<CancelRequest>(10);
let (cancel_sender, cancel_receiver) = mpsc::channel::<ActionServerCancelRequest>(10);
self.cancel_senders.insert(uuid.clone(), cancel_sender);
let gr: GoalRequest<T> = GoalRequest {
let gr: ActionServerGoalRequest<T> = ActionServerGoalRequest {
uuid,
goal,
cancel_requests: cancel_receiver,
@ -422,7 +414,7 @@ where
.get_mut(&uuid)
.and_then(|cancel_sender| {
let (s, r) = oneshot::channel::<(uuid::Uuid, bool)>();
let cr = CancelRequest {
let cr = ActionServerCancelRequest {
uuid: uuid.clone(),
response_sender: s,
};
@ -595,8 +587,9 @@ where
}
}
/// A handle to an active `Goal`
#[derive(Clone)]
pub struct ServerGoal<T>
pub struct ActionServerGoal<T>
where
T: WrappedActionTypeSupport,
{
@ -605,9 +598,9 @@ where
server: Weak<Mutex<dyn ActionServer_>>,
}
unsafe impl<T> Send for ServerGoal<T> where T: WrappedActionTypeSupport {}
unsafe impl<T> Send for ActionServerGoal<T> where T: WrappedActionTypeSupport {}
impl<T: 'static> ServerGoal<T>
impl<T: 'static> ActionServerGoal<T>
where
T: WrappedActionTypeSupport,
{

View File

@ -1,7 +1,18 @@
use super::*;
use futures::channel::oneshot;
use futures::TryFutureExt;
use std::future::Future;
use std::ffi::CString;
use std::mem::MaybeUninit;
use std::sync::{Mutex, Weak};
// Public facing apis
use crate::msg_types::*;
use crate::error::*;
use rcl::*;
/// ROS service client.
///
/// This is a handle to a service client wrapped in a `Mutex` inside a
/// `Weak` `Arc`. As such you can pass it between threads safely.
pub struct Client<T>
where
T: WrappedServiceTypeSupport,
@ -13,6 +24,9 @@ impl<T: 'static> Client<T>
where
T: WrappedServiceTypeSupport,
{
/// Make a service request.
///
/// Returns a `Future` of the `Response` type.
pub fn request(&self, msg: &T::Request) -> Result<impl Future<Output = Result<T::Response>>>
where
T: WrappedServiceTypeSupport,
@ -24,11 +38,24 @@ where
}
}
pub struct UntypedClient {
/// ROS "untyped" service client.
///
/// The untyped client is useful when you don't know the concrete type
/// at compile time. Messages are represented by `serde_json::Value`.
///
/// This is a handle to a service client wrapped in a `Mutex` inside a
/// `Weak` `Arc`. As such you can pass it between threads safely.
pub struct ClientUntyped {
client: Weak<Mutex<UntypedClient_>>,
}
impl UntypedClient {
impl ClientUntyped {
/// Make an "untyped" service request.
///
/// The request is a `serde_json::Value`. It is up to the user to
/// make sure the fields in the json object are correct.
///
/// Returns a `Future` of Result<serde_json::Value>.
pub fn request(
&self,
msg: serde_json::Value,
@ -47,8 +74,8 @@ where
Client { client }
}
pub fn make_untyped_client(client: Weak<Mutex<UntypedClient_>>) -> UntypedClient {
UntypedClient { client }
pub fn make_untyped_client(client: Weak<Mutex<UntypedClient_>>) -> ClientUntyped {
ClientUntyped { client }
}
unsafe impl<T> Send for TypedClient<T> where T: WrappedServiceTypeSupport {}
@ -342,7 +369,7 @@ where
}
}
impl IsAvailablePollable for UntypedClient {
impl IsAvailablePollable for ClientUntyped {
fn register_poll_available(&self, sender: oneshot::Sender<()>) -> Result<()> {
let client = self.client.upgrade().ok_or(Error::RCL_RET_CLIENT_INVALID)?;
let mut client = client.lock().unwrap();

View File

@ -1,5 +1,10 @@
use std::fmt::Debug;
use std::mem::MaybeUninit;
use std::time::Duration;
use super::*;
/// Different ROS clock types.
#[derive(Debug)]
pub enum ClockType {
RosTime,
@ -9,6 +14,7 @@ pub enum ClockType {
unsafe impl Send for Clock {}
/// A ROS clock.
pub struct Clock {
pub(crate) clock_handle: Box<rcl_clock_t>,
}
@ -22,6 +28,7 @@ pub fn clock_type_to_rcl(ct: &ClockType) -> rcl_clock_type_t {
}
impl Clock {
/// Create a new clock with the specified type.
pub fn create(ct: ClockType) -> Result<Clock> {
let mut clock_handle = MaybeUninit::<rcl_clock_t>::uninit();
@ -60,6 +67,7 @@ impl Clock {
Ok(dur)
}
/// TODO: move to builtin helper methods module.
pub fn to_builtin_time(d: &Duration) -> builtin_interfaces::msg::Time {
let sec = d.as_secs() as i32;
let nanosec = d.subsec_nanos();

View File

@ -1,13 +1,20 @@
use std::ffi::CString;
use std::fmt::Debug;
use std::ops::{Deref, DerefMut};
use std::sync::{Arc, Mutex};
use super::*;
/// A ROS context. Needed to create nodes etc.
#[derive(Debug, Clone)]
pub struct Context {
pub context_handle: Arc<Mutex<ContextHandle>>,
pub(crate) context_handle: Arc<Mutex<ContextHandle>>,
}
unsafe impl Send for Context {}
impl Context {
/// Create a ROS context.
pub fn create() -> Result<Context> {
let mut ctx: Box<rcl_context_t> = unsafe { Box::new(rcl_get_zero_initialized_context()) };
// argc/v
@ -52,6 +59,9 @@ impl Context {
}
}
/// Check if the ROS context is valid.
///
/// (This is abbreviated to rcl_ok() in the other bindings.)
pub fn is_valid(&self) -> bool {
let mut ctx = self.context_handle.lock().unwrap();
unsafe { rcl_context_is_valid(ctx.as_mut()) }

View File

@ -1,12 +1,18 @@
#![allow(non_camel_case_types)]
use actions::*;
use rcl::*;
use thiserror::Error;
/// r2r Result type.
pub type Result<T> = std::result::Result<T, Error>;
/// r2r Error type.
///
/// These values are mostly copied straight from the RCL headers, but
/// some are specific to r2r, such as `GoalCancelRejected` which does
/// not have an analogue in the rcl.
#[derive(Error, Debug)]
pub enum Error {
// Copied from the generated bindgen
#[error("RCL_RET_OK")]
RCL_RET_OK,
#[error("RCL_RET_ERROR")]
@ -150,6 +156,17 @@ impl Error {
_ if e == RCL_RET_INVALID_LOG_LEVEL_RULE => Error::RCL_RET_INVALID_LOG_LEVEL_RULE,
_ if e == RCL_RET_EVENT_INVALID => Error::RCL_RET_EVENT_INVALID,
_ if e == RCL_RET_EVENT_TAKE_FAILED => Error::RCL_RET_EVENT_TAKE_FAILED,
_ if e == RCL_RET_ACTION_NAME_INVALID => Error::RCL_RET_ACTION_NAME_INVALID,
_ if e == RCL_RET_ACTION_GOAL_ACCEPTED => Error::RCL_RET_ACTION_GOAL_ACCEPTED,
_ if e == RCL_RET_ACTION_GOAL_REJECTED => Error::RCL_RET_ACTION_GOAL_REJECTED,
_ if e == RCL_RET_ACTION_CLIENT_INVALID => Error::RCL_RET_ACTION_CLIENT_INVALID,
_ if e == RCL_RET_ACTION_CLIENT_TAKE_FAILED => Error::RCL_RET_ACTION_CLIENT_TAKE_FAILED,
_ if e == RCL_RET_ACTION_SERVER_INVALID => Error::RCL_RET_ACTION_SERVER_INVALID,
_ if e == RCL_RET_ACTION_SERVER_TAKE_FAILED => Error::RCL_RET_ACTION_SERVER_TAKE_FAILED,
_ if e == RCL_RET_ACTION_GOAL_HANDLE_INVALID => {
Error::RCL_RET_ACTION_GOAL_HANDLE_INVALID
}
_ if e == RCL_RET_ACTION_GOAL_EVENT_INVALID => Error::RCL_RET_ACTION_GOAL_EVENT_INVALID,
_ => panic!("TODO: add error code {}", e),
}
}

View File

@ -1,19 +1,73 @@
use std::collections::HashMap;
use std::ffi::{CStr, CString};
use std::fmt::Debug;
use std::marker::PhantomData;
use std::mem::MaybeUninit;
use std::ops::{Deref, DerefMut};
use std::sync::{Arc, Mutex, Weak};
use std::time::Duration;
//! Easy to use, runtime-agnostic async rust bindings for ROS2.
//! ---
//!
//! Minimal bindings for ROS2 that do *not* require hooking in to the
//! ROS2 build infrastructure -- `cargo build` is all you
//! need. Convenience Rust types are created by calling into the c
//! introspection libraries. This circumvents the ROS2 .msg/.idl
//! pipeline by relying on already generated C code. By default, the
//! behavior is to build bindings to the RCL and all message types
//! that can be found in the currently sourced ros environment.
//!
//! What works?
//!---
//!- Up to date with ROS2 ~Dashing~ ~Eloquent~ Foxy Galactic
//!- Building Rust types
//!- Publish/subscribe
//!- Services
//!- Actions
//!- Rudimentary parameter handling
//!
//! ---
//!
//! After having sourced ROS2 (see README for more details), you can
//! try the following example:
//!
//! ``` rust
//!use futures::executor::LocalPool;
//!use futures::future;
//!use futures::stream::StreamExt;
//!use futures::task::LocalSpawnExt;
//!use r2r;
//!
//!fn main() -> Result<(), Box<dyn std::error::Error>> {
//! let ctx = r2r::Context::create()?;
//! let mut node = r2r::Node::create(ctx, "node", "namespace")?;
//! let subscriber = node.subscribe::<r2r::std_msgs::msg::String>("/topic")?;
//! let publisher = node.create_publisher::<r2r::std_msgs::msg::String>("/topic")?;
//! let mut timer = node.create_wall_timer(std::time::Duration::from_millis(1000))?;
//!
//! // Set up a simple task executor.
//! let mut pool = LocalPool::new();
//! let spawner = pool.spawner();
//!
//! // Run the subscriber in one task, printing the messages
//! spawner.spawn_local(async move {
//! subscriber.for_each(|msg| {
//! println!("got new msg: {}", msg.data);
//! future::ready(())
//! }).await
//! })?;
//!
//! // Run the publisher in another task
//! spawner.spawn_local(async move {
//! let mut counter = 0;
//! loop {
//! let _elapsed = timer.tick().await.unwrap();
//! let msg = r2r::std_msgs::msg::String { data: format!("Hello, world! ({})", counter) };
//! publisher.publish(&msg).unwrap();
//! counter += 1;
//! }
//! })?;
//!
//! // Main thread spins ros.
//! loop {
//! node.spin_once(std::time::Duration::from_millis(100));
//! pool.run_until_stalled();
//! }
//!}
//! ```
use futures::channel::{mpsc, oneshot};
use futures::future::FutureExt;
use futures::future::TryFutureExt;
use futures::stream::{Stream, StreamExt};
use std::future::Future;
use retain_mut::RetainMut;
// otherwise crates using r2r needs to specify the same version of uuid as
// this crate depend on, which seem like bad user experience.
@ -47,19 +101,19 @@ use services::*;
mod clients;
use clients::*;
pub use clients::{Client, UntypedClient};
pub use clients::{Client, ClientUntyped};
mod action_clients;
use action_clients::*;
pub use action_clients::{ActionClient, ClientGoal, GoalStatus};
pub use action_clients::{ActionClient, ActionClientGoal, GoalStatus};
mod action_clients_untyped;
use action_clients_untyped::*;
pub use action_clients_untyped::{ActionClientUntyped, ClientGoalUntyped};
pub use action_clients_untyped::{ActionClientGoalUntyped, ActionClientUntyped};
mod action_servers;
use action_servers::*;
pub use action_servers::{ActionServer, CancelRequest, GoalRequest, ServerGoal};
pub use action_servers::{ActionServerCancelRequest, ActionServerGoal, ActionServerGoalRequest};
mod context;
pub use context::Context;

View File

@ -90,6 +90,9 @@ pub trait WrappedActionTypeSupport: Debug + Clone {
) -> unique_identifier_msgs::msg::UUID;
}
/// This struct wraps a RCL message.
///
/// It contains a pointer to a C struct.
#[derive(Debug)]
pub struct WrappedNativeMsg<T>
where

View File

@ -1,8 +1,25 @@
use super::*;
use futures::channel::{mpsc, oneshot};
use futures::future::FutureExt;
use futures::future::TryFutureExt;
use futures::future::{self, join_all};
use futures::stream::{Stream, StreamExt};
use std::future::Future;
use std::collections::HashMap;
use std::ffi::{CStr, CString};
use std::mem::MaybeUninit;
use std::sync::{Arc, Mutex};
use std::time::Duration;
use super::*;
/// A ROS Node.
///
/// This struct owns all subscribes, publishers, etc. To get events
/// from the ROS network into your ros application, `spin_once` should
/// be called continously.
pub struct Node {
context: Context,
/// ROS parameter values.
pub params: Arc<Mutex<HashMap<String, ParameterValue>>>,
node_handle: Box<rcl_node_t>,
// the node owns the subscribers
@ -378,7 +395,7 @@ impl Node {
&mut self,
service_name: &str,
service_type: &str,
) -> Result<UntypedClient> {
) -> Result<ClientUntyped> {
let service_type = UntypedServiceSupport::new_from(service_type)?;
let client_handle =
create_client_helper(self.node_handle.as_mut(), service_name, service_type.ts)?;
@ -479,7 +496,7 @@ impl Node {
pub fn create_action_server<T: 'static>(
&mut self,
action_name: &str,
) -> Result<impl Stream<Item = GoalRequest<T>> + Unpin>
) -> Result<impl Stream<Item = ActionServerGoalRequest<T>> + Unpin>
where
T: WrappedActionTypeSupport,
{
@ -497,7 +514,8 @@ impl Node {
}
let mut clock_handle = Box::new(unsafe { clock_handle.assume_init() });
let (goal_request_sender, goal_request_receiver) = mpsc::channel::<GoalRequest<T>>(10);
let (goal_request_sender, goal_request_receiver) =
mpsc::channel::<ActionServerGoalRequest<T>>(10);
let server_handle = create_action_server_helper(
self.node_handle.as_mut(),
@ -720,7 +738,8 @@ impl Node {
return;
}
let ws_subs = unsafe { std::slice::from_raw_parts(ws.subscriptions, self.subscribers.len()) };
let ws_subs =
unsafe { std::slice::from_raw_parts(ws.subscriptions, self.subscribers.len()) };
let mut subs_to_remove = vec![];
for (s, ws_s) in self.subscribers.iter_mut().zip(ws_subs) {
if ws_s != &std::ptr::null() {
@ -731,7 +750,8 @@ impl Node {
}
}
}
self.subscribers.retain(|s| !subs_to_remove.contains(s.handle()));
self.subscribers
.retain(|s| !subs_to_remove.contains(s.handle()));
let ws_timers = unsafe { std::slice::from_raw_parts(ws.timers, self.timers.len()) };
let mut timers_to_remove = vec![];
@ -768,7 +788,8 @@ impl Node {
}
}
}
self.services.retain(|s| !services_to_remove.contains(s.lock().unwrap().handle()));
self.services
.retain(|s| !services_to_remove.contains(s.lock().unwrap().handle()));
for ac in &self.action_clients {
let mut is_feedback_ready = false;
@ -968,9 +989,8 @@ impl Timer_ {
if is_ready {
let mut nanos = 0i64;
// todo: error handling
let ret = unsafe {
rcl_timer_get_time_since_last_call(&self.timer_handle, &mut nanos)
};
let ret =
unsafe { rcl_timer_get_time_since_last_call(&self.timer_handle, &mut nanos) };
if ret == RCL_RET_OK as i32 {
let ret = unsafe { rcl_timer_call(&mut self.timer_handle) };
if ret == RCL_RET_OK as i32 {

View File

@ -1,5 +1,8 @@
use std::ffi::CStr;
use super::*;
/// ROS parameter value.
#[derive(Debug, PartialEq, Clone)]
pub enum ParameterValue {
NotSet,

View File

@ -1,5 +1,11 @@
use std::ffi::CString;
use std::fmt::Debug;
use std::sync::Weak;
use std::marker::PhantomData;
use super::*;
// The publish function is thread safe. ROS2 docs state:
// =============
//
@ -27,6 +33,10 @@ use super::*;
unsafe impl<T> Send for Publisher<T> where T: WrappedTypesupport {}
/// A ROS (typed) publisher.
///
/// This contains a `Weak Arc` to a typed publisher. As such it is safe to
/// move between threads.
#[derive(Debug, Clone)]
pub struct Publisher<T>
where
@ -37,6 +47,11 @@ where
}
unsafe impl Send for PublisherUntyped {}
/// A ROS (untyped) publisher.
///
/// This contains a `Weak Arc` to an "untyped" publisher. As such it is safe to
/// move between threads.
#[derive(Debug, Clone)]
pub struct PublisherUntyped {
handle: Weak<rcl_publisher_t>,
@ -84,6 +99,9 @@ pub fn create_publisher_helper(
}
impl PublisherUntyped {
/// Publish an "untyped" ROS message represented by a `serde_json::Value`.
///
/// It is up to the user to make sure the fields are correct.
pub fn publish(&self, msg: serde_json::Value) -> Result<()> {
// upgrade to actual ref. if still alive
let publisher = self
@ -115,6 +133,7 @@ impl<T: 'static> Publisher<T>
where
T: WrappedTypesupport,
{
/// Publish a ROS message.
pub fn publish(&self, msg: &T) -> Result<()>
where
T: WrappedTypesupport,
@ -141,6 +160,10 @@ where
}
}
/// Publish a "native" ROS message.
///
/// This function is useful if you want to bypass the generated
/// rust types as it lets you work with the raw C struct.
pub fn publish_native(&self, msg: &WrappedNativeMsg<T>) -> Result<()>
where
T: WrappedTypesupport,

View File

@ -1,8 +1,17 @@
use futures::channel::{mpsc, oneshot};
use std::ffi::CString;
use std::sync::{Arc, Mutex, Weak};
use std::mem::MaybeUninit;
use super::*;
/// Encapsulates a service request. In contrast to having a simply callback from
/// Request -> Response types that is called synchronously, the service request
/// can be moved around and completed asynchronously.
/// Encapsulates a service request.
///
/// In contrast to having a callback from Request -> Response
/// types that is called synchronously, the service request can be
/// moved around and completed asynchronously.
///
/// To complete the request, call the `respond` function.
#[derive(Clone)]
pub struct ServiceRequest<T>
where
@ -95,7 +104,7 @@ where
return true;
}
eprintln!("warning: could not send service request ({})", e)
},
}
_ => (),
}
} // TODO handle failure.

View File

@ -1,3 +1,6 @@
use futures::channel::mpsc;
use std::ffi::CString;
use super::*;
pub trait Subscriber_ {

View File

@ -12,7 +12,8 @@ pub(crate) fn log_guard() -> MutexGuard<'static, ()> {
LOG_GUARD.lock().unwrap()
}
/// Don't call this directly, use the macros below instead.
/// Don't call this directly, use the logging macros instead.
#[doc(hidden)]
pub fn log(msg: &str, logger_name: &str, file: &str, line: u32, severity: LogSeverity) {
let _guard = log_guard();
let is_init = unsafe { g_rcutils_logging_initialized };
@ -47,7 +48,7 @@ pub fn log(msg: &str, logger_name: &str, file: &str, line: u32, severity: LogSev
}
}
// pub because of our macros
/// Logging severity
pub enum LogSeverity {
Unset,
Debug,
@ -86,6 +87,7 @@ macro_rules! __impl_log {
}};
}
/// Debug log message.
#[macro_export]
macro_rules! log_debug {
($logger_name:expr, $($args:tt)*) => {{
@ -94,6 +96,7 @@ macro_rules! log_debug {
}}
}
/// Info log message.
#[macro_export]
macro_rules! log_info {
($logger_name:expr, $($args:tt)*) => {{
@ -102,6 +105,7 @@ macro_rules! log_info {
}}
}
/// Warning log message.
#[macro_export]
macro_rules! log_warn {
($logger_name:expr, $($args:tt)*) => {{
@ -110,6 +114,7 @@ macro_rules! log_warn {
}}
}
/// Error log message.
#[macro_export]
macro_rules! log_error {
($logger_name:expr, $($args:tt)*) => {{
@ -118,6 +123,7 @@ macro_rules! log_error {
}}
}
/// Fatal log message.
#[macro_export]
macro_rules! log_fatal {
($logger_name:expr, $($args:tt)*) => {{