Skip to content

Timers #480

New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

Open
wants to merge 29 commits into
base: main
Choose a base branch
from
Open
Show file tree
Hide file tree
Changes from all commits
Commits
Show all changes
29 commits
Select commit Hold shift + click to select a range
837f248
Squash async worker changes
mxgrey May 12, 2025
97c341d
Fix bug in logging macros
mxgrey May 13, 2025
49f5065
Clean up examples using new API
mxgrey May 13, 2025
5f6015a
Ensure workers wake up when a task is run
mxgrey May 13, 2025
c8f61f0
Iterating on documentation
mxgrey May 13, 2025
a27bb89
Update docs for subscriptions
mxgrey May 14, 2025
402a9c9
Fix create_worker bug
mxgrey May 14, 2025
1d8c468
Add more documentation for Worker
mxgrey May 14, 2025
f0c2e09
Fix all todos that can be addressed for now
mxgrey May 14, 2025
4617c9f
Add introductory documentation and a parameter demo
mxgrey May 14, 2025
1489807
Add documentation for parameters
mxgrey May 14, 2025
1f4a8b9
Fix formatting
mxgrey May 14, 2025
ac57416
Remove residual directory
mxgrey May 14, 2025
e482b2d
Port over timer modules
mxgrey May 14, 2025
63c0e88
Add timer demo
mxgrey May 14, 2025
7eba15d
Port over packaging fix
mxgrey May 14, 2025
1986ebb
Fix formatting for examples
mxgrey May 14, 2025
5a5d156
Merge branch 'worker' into worker_with_timers
mxgrey May 14, 2025
e8f037f
use timer
mxgrey May 14, 2025
f1ad6d8
Fix distro divergence in guid type
mxgrey May 14, 2025
9f58194
Merge branch 'worker' into worker_with_timers
mxgrey May 14, 2025
fd2079b
Fix compilation bug in 1.75
mxgrey May 14, 2025
b9d65b1
Force backtrace version that is compatible with 1.75
mxgrey May 14, 2025
3c256be
fix merge
mxgrey May 14, 2025
c9067b2
Merge branch 'worker' into worker_with_timers
mxgrey May 14, 2025
8f89860
fix merge conflicts
mxgrey May 15, 2025
27bf1e2
Merge branch 'worker' into worker_with_timers
mxgrey May 15, 2025
4adc857
Fix formatting
mxgrey May 15, 2025
a2af202
Fix formatting
mxgrey May 15, 2025
File filter

Filter by extension

Filter by extension


Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
8 changes: 8 additions & 0 deletions examples/logging_demo/Cargo.toml
Original file line number Diff line number Diff line change
@@ -0,0 +1,8 @@
[package]
name = "logging_demo"
version = "0.1.0"
edition = "2021"

[dependencies]
rclrs = "0.4"
example_interfaces = "*"
21 changes: 21 additions & 0 deletions examples/logging_demo/package.xml
Original file line number Diff line number Diff line change
@@ -0,0 +1,21 @@
<?xml version="1.0"?>
<?xml-model
href="http://download.ros.org/schema/package_format3.xsd"
schematypens="http://www.w3.org/2001/XMLSchema"?>
<package format="3">
<name>examples_logging_demo</name>
<maintainer email="[email protected]">Esteve Fernandez</maintainer>
<!-- This project is not military-sponsored, Jacob's employment contract just requires him to use this email address -->
<maintainer email="[email protected]">Jacob Hassold</maintainer>
<version>0.4.1</version>
<description>Package containing an example of how to use a worker in rclrs.</description>
<license>Apache License 2.0</license>

<depend>rclrs</depend>
<depend>rosidl_runtime_rs</depend>
<depend>example_interfaces</depend>

<export>
<build_type>ament_cargo</build_type>
</export>
</package>
39 changes: 39 additions & 0 deletions examples/logging_demo/src/main.rs
Original file line number Diff line number Diff line change
@@ -0,0 +1,39 @@
use rclrs::*;
use std::time::Duration;

fn main() -> Result<(), RclrsError> {
let mut executor = Context::default_from_env()?.create_basic_executor();
let node = executor.create_node("logging_demo")?;

let _subscription = node.clone().create_subscription(
"logging_demo",
move |msg: example_interfaces::msg::String| {
let data = msg.data;

// You can apply modifiers such as .once() to node.logger()
// to dictate how the logging behaves.
log!(node.logger().once(), "First message: {data}",);

log!(node.logger().skip_first(), "Subsequent message: {data}",);

// You can chain multiple modifiers together.
log_warn!(
node.logger().skip_first().throttle(Duration::from_secs(5)),
"Throttled message: {data}",
);
},
)?;

// Any &str can be used as the logger name and have
// logging modifiers applied to it.
log_info!(
"notice".once(),
"Ready to begin logging example_interfaces/msg/String messages published to 'logging_demo'.",
);
log_warn!(
"help",
"Try running\n \
$ ros2 topic pub logging_demo example_interfaces/msg/String \"data: message\"",
);
executor.spin(SpinOptions::default()).first_error()
}
37 changes: 16 additions & 21 deletions examples/minimal_client_service/src/minimal_client.rs
Original file line number Diff line number Diff line change
@@ -1,36 +1,31 @@
use anyhow::{Error, Result};
use example_interfaces::srv::*;
use rclrs::*;

fn main() -> Result<(), Error> {
let mut executor = Context::default_from_env()?.create_basic_executor();

let node = executor.create_node("minimal_client")?;

let client = node.create_client::<example_interfaces::srv::AddTwoInts>("add_two_ints")?;
let client = node.create_client::<AddTwoInts>("add_two_ints")?;

let request = example_interfaces::srv::AddTwoInts_Request { a: 41, b: 1 };
let promise = executor.commands().run(async move {
println!("Waiting for service...");
client.notify_on_service_ready().await.unwrap();

println!("Starting client");
let request = AddTwoInts_Request { a: 41, b: 1 };

while !client.service_is_ready()? {
std::thread::sleep(std::time::Duration::from_millis(10));
}
println!("Waiting for response");
let response: AddTwoInts_Response = client.call(&request).unwrap().await.unwrap();

client.async_send_request_with_callback(
&request,
move |response: example_interfaces::srv::AddTwoInts_Response| {
println!(
"Result of {} + {} is: {}",
request.a, request.b, response.sum
);
},
)?;
println!(
"Result of {} + {} is: {}",
request.a, request.b, response.sum,
);
});

std::thread::sleep(std::time::Duration::from_millis(500));

println!("Waiting for response");
executor
.spin(SpinOptions::default())
.first_error()
.map_err(|err| err.into())
.spin(SpinOptions::new().until_promise_resolved(promise))
.first_error()?;
Ok(())
}
27 changes: 14 additions & 13 deletions examples/minimal_client_service/src/minimal_client_async.rs
Original file line number Diff line number Diff line change
@@ -1,4 +1,5 @@
use anyhow::{Error, Result};
use example_interfaces::srv::*;
use rclrs::*;

#[tokio::main]
Expand All @@ -7,28 +8,28 @@ async fn main() -> Result<(), Error> {

let node = executor.create_node("minimal_client")?;

let client = node.create_client::<example_interfaces::srv::AddTwoInts>("add_two_ints")?;
let client = node.create_client::<AddTwoInts>("add_two_ints")?;

println!("Starting client");

while !client.service_is_ready()? {
std::thread::sleep(std::time::Duration::from_millis(10));
}

let request = example_interfaces::srv::AddTwoInts_Request { a: 41, b: 1 };
let request = AddTwoInts_Request { a: 41, b: 1 };

let future = client.call_async(&request);
let promise = client
.call_then(&request, move |response: AddTwoInts_Response| {
println!(
"Result of {} + {} is: {}",
request.a, request.b, response.sum,
);
})
.unwrap();

println!("Waiting for response");

let rclrs_spin = tokio::task::spawn_blocking(move || executor.spin(SpinOptions::default()));

let response = future.await?;
println!(
"Result of {} + {} is: {}",
request.a, request.b, response.sum
);

rclrs_spin.await.ok();
executor
.spin(SpinOptions::new().until_promise_resolved(promise))
.first_error()?;
Ok(())
}
24 changes: 12 additions & 12 deletions examples/minimal_client_service/src/minimal_service.rs
Original file line number Diff line number Diff line change
@@ -1,12 +1,15 @@
use anyhow::{Error, Result};
use example_interfaces::srv::*;
use rclrs::*;

fn handle_service(
_request_header: &rclrs::rmw_request_id_t,
request: example_interfaces::srv::AddTwoInts_Request,
) -> example_interfaces::srv::AddTwoInts_Response {
println!("request: {} + {}", request.a, request.b);
example_interfaces::srv::AddTwoInts_Response {
fn handle_service(request: AddTwoInts_Request, info: ServiceInfo) -> AddTwoInts_Response {
let timestamp = info
.received_timestamp
.map(|t| format!(" at [{t:?}]"))
.unwrap_or(String::new());

println!("request{timestamp}: {} + {}", request.a, request.b);
AddTwoInts_Response {
sum: request.a + request.b,
}
}
Expand All @@ -16,12 +19,9 @@ fn main() -> Result<(), Error> {

let node = executor.create_node("minimal_service")?;

let _server = node
.create_service::<example_interfaces::srv::AddTwoInts, _>("add_two_ints", handle_service)?;
let _server = node.create_service::<AddTwoInts, _>("add_two_ints", handle_service)?;

println!("Starting server");
executor
.spin(SpinOptions::default())
.first_error()
.map_err(|err| err.into())
executor.spin(SpinOptions::default()).first_error()?;
Ok(())
}
2 changes: 1 addition & 1 deletion examples/minimal_pub_sub/Cargo.toml
Original file line number Diff line number Diff line change
Expand Up @@ -29,7 +29,7 @@ path = "src/zero_copy_publisher.rs"
anyhow = {version = "1", features = ["backtrace"]}
rclrs = "0.4"
rosidl_runtime_rs = "0.4"
std_msgs = "*"
example_interfaces = "*"

# This specific version is compatible with Rust 1.75
backtrace = "=0.3.74"
Expand Down
4 changes: 2 additions & 2 deletions examples/minimal_pub_sub/package.xml
Original file line number Diff line number Diff line change
Expand Up @@ -14,11 +14,11 @@

<build_depend>rclrs</build_depend>
<build_depend>rosidl_runtime_rs</build_depend>
<build_depend>std_msgs</build_depend>
<build_depend>example_interfaces</build_depend>

<exec_depend>rclrs</exec_depend>
<exec_depend>rosidl_runtime_rs</exec_depend>
<exec_depend>std_msgs</exec_depend>
<exec_depend>example_interfaces</exec_depend>

<export>
<build_type>ament_cargo</build_type>
Expand Down
4 changes: 2 additions & 2 deletions examples/minimal_pub_sub/src/minimal_publisher.rs
Original file line number Diff line number Diff line change
Expand Up @@ -7,9 +7,9 @@ fn main() -> Result<(), Error> {

let node = executor.create_node("minimal_publisher")?;

let publisher = node.create_publisher::<std_msgs::msg::String>("topic")?;
let publisher = node.create_publisher::<example_interfaces::msg::String>("topic")?;

let mut message = std_msgs::msg::String::default();
let mut message = example_interfaces::msg::String::default();

let mut publish_count: u32 = 1;

Expand Down
19 changes: 8 additions & 11 deletions examples/minimal_pub_sub/src/minimal_subscriber.rs
Original file line number Diff line number Diff line change
Expand Up @@ -7,19 +7,16 @@ fn main() -> Result<(), Error> {

let node = executor.create_node("minimal_subscriber")?;

let mut num_messages: usize = 0;

let _subscription = node.create_subscription::<std_msgs::msg::String, _>(
let worker = node.create_worker::<usize>(0);
let _subscription = worker.create_subscription::<example_interfaces::msg::String, _>(
"topic",
move |msg: std_msgs::msg::String| {
num_messages += 1;
println!("I heard: '{}'", msg.data);
println!("(Got {} messages so far)", num_messages);
move |num_messages: &mut usize, msg: example_interfaces::msg::String| {
*num_messages += 1;
println!("#{} | I heard: '{}'", *num_messages, msg.data);
},
)?;

executor
.spin(SpinOptions::default())
.first_error()
.map_err(|err| err.into())
println!("Waiting for messages...");
executor.spin(SpinOptions::default()).first_error()?;
Ok(())
}
78 changes: 36 additions & 42 deletions examples/minimal_pub_sub/src/minimal_two_nodes.rs
Original file line number Diff line number Diff line change
@@ -1,47 +1,41 @@
use rclrs::*;
use std::sync::{
atomic::{AtomicU32, Ordering},
Arc, Mutex,
};
use std::sync::Arc;

use anyhow::{Error, Result};

struct MinimalSubscriber {
num_messages: AtomicU32,
struct MinimalSubscriberNode {
#[allow(unused)]
subscription: WorkerSubscription<example_interfaces::msg::String, SubscriptionData>,
}

struct SubscriptionData {
node: Node,
subscription: Mutex<Option<Subscription<std_msgs::msg::String>>>,
num_messages: usize,
}

impl MinimalSubscriber {
pub fn new(executor: &Executor, name: &str, topic: &str) -> Result<Arc<Self>, RclrsError> {
impl MinimalSubscriberNode {
pub fn new(executor: &Executor, name: &str, topic: &str) -> Result<Self, RclrsError> {
let node = executor.create_node(name)?;
let minimal_subscriber = Arc::new(MinimalSubscriber {
num_messages: 0.into(),
node,
subscription: None.into(),

let worker = node.create_worker::<SubscriptionData>(SubscriptionData {
node: Arc::clone(&node),
num_messages: 0,
});

let minimal_subscriber_aux = Arc::clone(&minimal_subscriber);
let subscription = minimal_subscriber
.node
.create_subscription::<std_msgs::msg::String, _>(
topic,
move |msg: std_msgs::msg::String| {
minimal_subscriber_aux.callback(msg);
},
)?;
*minimal_subscriber.subscription.lock().unwrap() = Some(subscription);
Ok(minimal_subscriber)
}
let subscription = worker.create_subscription(
topic,
|data: &mut SubscriptionData, msg: example_interfaces::msg::String| {
data.num_messages += 1;
println!("[{}] I heard: '{}'", data.node.name(), msg.data);
println!(
"[{}] (Got {} messages so far)",
data.node.name(),
data.num_messages,
);
},
)?;

fn callback(&self, msg: std_msgs::msg::String) {
self.num_messages.fetch_add(1, Ordering::SeqCst);
println!("[{}] I heard: '{}'", self.node.name(), msg.data);
println!(
"[{}] (Got {} messages so far)",
self.node.name(),
self.num_messages.load(Ordering::SeqCst)
);
Ok(MinimalSubscriberNode { subscription })
}
}

Expand All @@ -50,14 +44,16 @@ fn main() -> Result<(), Error> {
let publisher_node = executor.create_node("minimal_publisher")?;

let _subscriber_node_one =
MinimalSubscriber::new(&executor, "minimal_subscriber_one", "topic")?;
MinimalSubscriberNode::new(&executor, "minimal_subscriber_one", "topic")?;
let _subscriber_node_two =
MinimalSubscriber::new(&executor, "minimal_subscriber_two", "topic")?;
MinimalSubscriberNode::new(&executor, "minimal_subscriber_two", "topic")?;

let publisher = publisher_node.create_publisher::<std_msgs::msg::String>("topic")?;
let publisher = publisher_node.create_publisher::<example_interfaces::msg::String>("topic")?;

std::thread::spawn(move || -> Result<(), RclrsError> {
let mut message = std_msgs::msg::String::default();
// TODO(@mxgrey): Replace this with a timer once we have the Timer feature
// merged in.
std::thread::spawn(move || -> Result<(), rclrs::RclrsError> {
let mut message = example_interfaces::msg::String::default();
let mut publish_count: u32 = 1;
loop {
message.data = format!("Hello, world! {}", publish_count);
Expand All @@ -68,8 +64,6 @@ fn main() -> Result<(), Error> {
}
});

executor
.spin(SpinOptions::default())
.first_error()
.map_err(|err| err.into())
executor.spin(rclrs::SpinOptions::default()).first_error()?;
Ok(())
}
2 changes: 1 addition & 1 deletion examples/minimal_pub_sub/src/zero_copy_publisher.rs
Original file line number Diff line number Diff line change
Expand Up @@ -7,7 +7,7 @@ fn main() -> Result<(), Error> {

let node = executor.create_node("minimal_publisher")?;

let publisher = node.create_publisher::<std_msgs::msg::rmw::UInt32>("topic")?;
let publisher = node.create_publisher::<example_interfaces::msg::rmw::UInt32>("topic")?;

let mut publish_count: u32 = 1;

Expand Down
Loading
Loading