-
Notifications
You must be signed in to change notification settings - Fork 170
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
base: main
Are you sure you want to change the base?
Timers #480
Changes from all commits
2d20c4e
c9c2127
7ad4ece
802925b
f24b978
9b6b1d1
73b34b3
030f59c
82f4da6
a589997
a4fa5cb
35fa24a
775b170
771920d
2780db7
2e2dce0
421784b
File filter
Filter by extension
Conversations
Jump to
Diff view
Diff view
There are no files selected for viewing
Original file line number | Diff line number | Diff line change |
---|---|---|
@@ -0,0 +1,12 @@ | ||
[package] | ||
name = "examples_timer_demo" | ||
version = "0.1.0" | ||
edition = "2021" | ||
|
||
[[bin]] | ||
name = "timer_demo" | ||
path = "src/main.rs" | ||
|
||
[dependencies] | ||
rclrs = "0.4" | ||
example_interfaces = "*" |
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_timer_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> |
Original file line number | Diff line number | Diff line change |
---|---|---|
@@ -0,0 +1,22 @@ | ||
/// Creates a SimpleTimerNode, initializes a node and the timer with a callback | ||
/// that prints the timer callback execution iteration. The callback is executed | ||
/// thanks to the spin, which is in charge of executing the timer's events among | ||
/// other entities' events. | ||
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("timer_demo")?; | ||
let worker = node.create_worker::<usize>(0); | ||
let timer_period = Duration::from_secs(1); | ||
let _timer = worker.create_timer_repeating(timer_period, move |count: &mut usize| { | ||
*count += 1; | ||
println!( | ||
"Drinking 🧉 for the {}th time every {:?}.", | ||
There was a problem hiding this comment. Choose a reason for hiding this commentThe reason will be displayed to describe this comment to others. Learn more. Works for me and is a nice example :) Does ROS2 have an example like this actually? Not used in the tutorials right? I guess the only nitpick would be, that all other python/cpp examples use There was a problem hiding this comment. Choose a reason for hiding this commentThe reason will be displayed to describe this comment to others. Learn more. See this reply. |
||
*count, timer_period, | ||
); | ||
})?; | ||
|
||
executor.spin(SpinOptions::default()).first_error() | ||
} |
Original file line number | Diff line number | Diff line change |
---|---|---|
|
@@ -29,12 +29,14 @@ use async_std::future::timeout; | |
use rosidl_runtime_rs::Message; | ||
|
||
use crate::{ | ||
rcl_bindings::*, Client, ClientOptions, ClientState, Clock, ContextHandle, ExecutorCommands, | ||
IntoAsyncServiceCallback, IntoAsyncSubscriptionCallback, IntoNodeServiceCallback, | ||
IntoNodeSubscriptionCallback, LogParams, Logger, ParameterBuilder, ParameterInterface, | ||
ParameterVariant, Parameters, Promise, Publisher, PublisherOptions, PublisherState, RclrsError, | ||
Service, ServiceOptions, ServiceState, Subscription, SubscriptionOptions, SubscriptionState, | ||
TimeSource, ToLogParams, Worker, WorkerOptions, WorkerState, ENTITY_LIFECYCLE_MUTEX, | ||
rcl_bindings::*, AnyTimerCallback, Client, ClientOptions, ClientState, Clock, ContextHandle, | ||
ExecutorCommands, IntoAsyncServiceCallback, IntoAsyncSubscriptionCallback, | ||
IntoNodeServiceCallback, IntoNodeSubscriptionCallback, IntoNodeTimerOneshotCallback, | ||
IntoNodeTimerRepeatingCallback, IntoTimerOptions, LogParams, Logger, ParameterBuilder, | ||
ParameterInterface, ParameterVariant, Parameters, Promise, Publisher, PublisherOptions, | ||
PublisherState, RclrsError, Service, ServiceOptions, ServiceState, Subscription, | ||
SubscriptionOptions, SubscriptionState, TimeSource, Timer, TimerState, ToLogParams, Worker, | ||
WorkerOptions, WorkerState, ENTITY_LIFECYCLE_MUTEX, | ||
}; | ||
|
||
/// A processing unit that can communicate with other nodes. See the API of | ||
|
@@ -893,6 +895,216 @@ impl NodeState { | |
) | ||
} | ||
|
||
/// Create a [`Timer`] with a repeating callback. | ||
There was a problem hiding this comment. Choose a reason for hiding this commentThe reason will be displayed to describe this comment to others. Learn more. I was first confused on why there were some much commented out lines, but then I realized that this was for the documentation. Nice! |
||
/// | ||
/// See also: | ||
/// * [`Self::create_timer_oneshot`] | ||
/// * [`Self::create_timer_inert`] | ||
/// | ||
/// # Behavior | ||
/// | ||
/// While the callback of this timer is running, no other callbacks associated | ||
/// with this node will be able to run. This is in contrast to callbacks given | ||
/// to [`Self::create_subscription`] which can run multiple times in parallel. | ||
/// | ||
/// Since the callback of this timer may block other callbacks from being able | ||
/// to run, it is strongly recommended to ensure that the callback returns | ||
/// quickly. If the callback needs to trigger long-running behavior then you | ||
/// can consider using [`std::thread::spawn`], or for async behaviors you can | ||
/// capture an [`ExecutorCommands`] in your callback and use [`ExecutorCommands::run`] | ||
/// to issue a task for the executor to run in its async task pool. | ||
/// | ||
/// Since these callbacks are blocking, you may use [`FnMut`] here instead of | ||
/// being limited to [`Fn`]. | ||
/// | ||
/// # Timer Options | ||
/// | ||
/// You can choose both | ||
/// 1. a timer period (duration) which determines how often the callback is triggered | ||
/// 2. a clock to measure the passage of time | ||
/// | ||
/// Both of these choices are expressed by [`TimerOptions`][1]. | ||
/// | ||
/// By default the steady clock time will be used, but you could choose | ||
/// node time instead if you want the timer to automatically use simulated | ||
/// time when running as part of a simulation: | ||
/// ``` | ||
/// # use rclrs::*; | ||
/// # let executor = Context::default().create_basic_executor(); | ||
/// # let node = executor.create_node("my_node").unwrap(); | ||
/// use std::time::Duration; | ||
/// | ||
/// let timer = node.create_timer_repeating( | ||
/// TimerOptions::new(Duration::from_secs(1)) | ||
/// .node_time(), | ||
/// || { | ||
/// println!("Triggering once each simulated second"); | ||
/// }, | ||
/// )?; | ||
/// # Ok::<(), RclrsError>(()) | ||
/// ``` | ||
/// | ||
/// If there is a specific manually-driven clock you want to use, you can | ||
/// also select that: | ||
/// ``` | ||
/// # use rclrs::*; | ||
/// # let executor = Context::default().create_basic_executor(); | ||
/// # let node = executor.create_node("my_node").unwrap(); | ||
/// use std::time::Duration; | ||
/// | ||
/// let (my_clock, my_source) = Clock::with_source(); | ||
/// | ||
/// let timer = node.create_timer_repeating( | ||
/// TimerOptions::new(Duration::from_secs(1)) | ||
/// .clock(&my_clock), | ||
/// || { | ||
/// println!("Triggering once each simulated second"); | ||
/// }, | ||
/// )?; | ||
/// | ||
/// my_source.set_ros_time_override(1_500_000_000); | ||
/// # Ok::<(), RclrsError>(()) | ||
/// ``` | ||
/// | ||
/// If you are okay with the default choice of clock (steady clock) then you | ||
/// can choose to simply pass a duration in as the options: | ||
/// ``` | ||
/// # use rclrs::*; | ||
/// # let executor = Context::default().create_basic_executor(); | ||
/// # let node = executor.create_node("my_node").unwrap(); | ||
/// use std::time::Duration; | ||
/// | ||
/// let timer = node.create_timer_repeating( | ||
/// Duration::from_secs(1), | ||
/// || { | ||
/// println!("Triggering per steady clock second"); | ||
/// }, | ||
/// )?; | ||
/// # Ok::<(), RclrsError>(()) | ||
/// ``` | ||
/// | ||
/// # Node Timer Repeating Callbacks | ||
/// | ||
/// Node Timer repeating callbacks support three signatures: | ||
/// - <code>[FnMut] ()</code> | ||
/// - <code>[FnMut] ([Time][2])</code> | ||
/// - <code>[FnMut] (&[Timer])</code> | ||
/// | ||
/// You can choose to receive the current time when the callback is being | ||
/// triggered. | ||
/// | ||
/// Or instead of the current time, you can get a borrow of the [`Timer`] | ||
/// itself, that way if you need to access it from inside the callback, you | ||
/// do not need to worry about capturing a [`Weak`][3] and then locking it. | ||
/// This is useful if you need to change the callback of the timer from inside | ||
/// the callback of the timer. | ||
/// | ||
/// For an [`FnOnce`] instead of [`FnMut`], use [`Self::create_timer_oneshot`]. | ||
/// | ||
/// [1]: crate::TimerOptions | ||
/// [2]: crate::Time | ||
/// [3]: std::sync::Weak | ||
pub fn create_timer_repeating<'a, Args>( | ||
self: &Arc<Self>, | ||
options: impl IntoTimerOptions<'a>, | ||
callback: impl IntoNodeTimerRepeatingCallback<Args>, | ||
) -> Result<Timer, RclrsError> { | ||
self.create_timer(options, callback.into_node_timer_repeating_callback()) | ||
} | ||
|
||
/// Create a [`Timer`] whose callback will be triggered once after the period | ||
/// of the timer has elapsed. After that you will need to use | ||
/// [`TimerState::set_repeating`] or [`TimerState::set_oneshot`] or else | ||
/// nothing will happen the following times that the `Timer` elapses. | ||
/// | ||
/// See also: | ||
/// * [`Self::create_timer_repeating`] | ||
/// * [`Self::create_timer_inert`] | ||
/// | ||
/// # Behavior | ||
/// | ||
/// While the callback of this timer is running, no other callbacks associated | ||
/// with this node will be able to run. This is in contrast to callbacks given | ||
/// to [`Self::create_subscription`] which can run multiple times in parallel. | ||
/// | ||
/// Since the callback of this timer may block other callbacks from being able | ||
/// to run, it is strongly recommended to ensure that the callback returns | ||
/// quickly. If the callback needs to trigger long-running behavior then you | ||
/// can consider using [`std::thread::spawn`], or for async behaviors you can | ||
/// capture an [`ExecutorCommands`] in your callback and use [`ExecutorCommands::run`] | ||
/// to issue a task for the executor to run in its async task pool. | ||
/// | ||
/// Since these callbacks will only be triggered once, you may use [`FnOnce`] here. | ||
/// | ||
/// # Timer Options | ||
/// | ||
/// See [`NodeSate::create_timer_repeating`][3] for examples of setting the | ||
/// timer options. | ||
/// | ||
/// # Node Timer Oneshot Callbacks | ||
/// | ||
/// Node Timer repeating callbacks support three signatures: | ||
/// - <code>[FnMut] ()</code> | ||
/// - <code>[FnMut] ([Time][2])</code> | ||
/// - <code>[FnMut] (&[Timer])</code> | ||
/// | ||
/// You can choose to receive the current time when the callback is being | ||
/// triggered. | ||
/// | ||
/// Or instead of the current time, you can get a borrow of the [`Timer`] | ||
/// itself, that way if you need to access it from inside the callback, you | ||
/// do not need to worry about capturing a [`Weak`][3] and then locking it. | ||
/// This is useful if you need to change the callback of the timer from inside | ||
/// the callback of the timer. | ||
/// | ||
/// [2]: crate::Time | ||
/// [3]: std::sync::Weak | ||
pub fn create_timer_oneshot<'a, Args>( | ||
self: &Arc<Self>, | ||
options: impl IntoTimerOptions<'a>, | ||
callback: impl IntoNodeTimerOneshotCallback<Args>, | ||
) -> Result<Timer, RclrsError> { | ||
self.create_timer(options, callback.into_node_timer_oneshot_callback()) | ||
} | ||
|
||
/// Create a [`Timer`] without a callback. Nothing will happen when this | ||
/// `Timer` elapses until you use [`TimerState::set_repeating`] or | ||
/// [`TimerState::set_oneshot`]. | ||
/// | ||
/// See also: | ||
/// * [`Self::create_timer_repeating`] | ||
/// * [`Self::create_timer_oneshot`] | ||
pub fn create_timer_inert<'a>( | ||
self: &Arc<Self>, | ||
options: impl IntoTimerOptions<'a>, | ||
) -> Result<Timer, RclrsError> { | ||
self.create_timer(options, AnyTimerCallback::Inert) | ||
} | ||
|
||
/// Used internally to create a [`Timer`]. | ||
/// | ||
/// Downstream users should instead use: | ||
/// * [`Self::create_timer_repeating`] | ||
/// * [`Self::create_timer_oneshot`] | ||
/// * [`Self::create_timer_inert`] | ||
fn create_timer<'a>( | ||
self: &Arc<Self>, | ||
options: impl IntoTimerOptions<'a>, | ||
callback: AnyTimerCallback<Node>, | ||
) -> Result<Timer, RclrsError> { | ||
let options = options.into_timer_options(); | ||
let clock = options.clock.as_clock(self); | ||
let node = options.clock.is_node_time().then(|| Arc::clone(self)); | ||
TimerState::create( | ||
options.period, | ||
clock, | ||
callback, | ||
self.commands.async_worker_commands(), | ||
&self.handle.context_handle, | ||
node, | ||
) | ||
} | ||
|
||
/// Returns the ROS domain ID that the node is using. | ||
/// | ||
/// The domain ID controls which nodes can send messages to each other, see the [ROS 2 concept article][1]. | ||
|
There was a problem hiding this comment.
Choose a reason for hiding this comment
The reason will be displayed to describe this comment to others. Learn more.
Maybe good to have a bin here so that we can run it through ROS2 command?
There was a problem hiding this comment.
Choose a reason for hiding this comment
The reason will be displayed to describe this comment to others. Learn more.
Is this what you had in mind?
Since the example is in
src/main.rs
, by default it will generate a binary with the same name as the package,examples_timer_demo
. But I see in the other example packages there's a certain naming pattern for the binaries, so now I've copied that pattern here.There was a problem hiding this comment.
Choose a reason for hiding this comment
The reason will be displayed to describe this comment to others. Learn more.
ahhh gotcha.
And yes exactly like that. naming consistency is good :)