Skip to content

Commit 5df379f

Browse files
Refactor API to use ClockSource
Signed-off-by: Luca Della Vedova <lucadv@intrinsic.ai>
1 parent d7bb9f2 commit 5df379f

File tree

5 files changed

+128
-91
lines changed

5 files changed

+128
-91
lines changed

rclrs/src/clock.rs

Lines changed: 86 additions & 43 deletions
Original file line numberDiff line numberDiff line change
@@ -1,6 +1,6 @@
11
use crate::rcl_bindings::*;
22
use crate::{error::ToResult, time::Time, to_rclrs_result, RclrsError};
3-
use std::sync::Mutex;
3+
use std::sync::{Arc, Mutex};
44

55
/// Enum to describe clock type. Redefined for readability and to eliminate the uninitialized case
66
/// from the `rcl_clock_type_t` enum in the binding.
@@ -28,14 +28,53 @@ impl From<ClockType> for rcl_clock_type_t {
2828
/// Struct that implements a Clock and wraps `rcl_clock_t`.
2929
pub struct Clock {
3030
_type: ClockType,
31-
_rcl_clock: Mutex<rcl_clock_t>,
31+
_rcl_clock: Arc<Mutex<rcl_clock_t>>,
3232
// TODO(luca) Implement jump callbacks
3333
}
3434

35+
/// A clock source that can be used to drive the contained clock. Created when a clock of type
36+
/// `ClockType::RosTime` is constructed
37+
pub struct ClockSource {
38+
_rcl_clock: Arc<Mutex<rcl_clock_t>>,
39+
}
40+
3541
impl Clock {
42+
/// Creates a new Clock with `ClockType::SystemTime`
43+
pub fn system() -> Result<Self, RclrsError> {
44+
Self::make(ClockType::SystemTime)
45+
}
46+
47+
/// Creates a new Clock with `ClockType::SteadyTime`
48+
pub fn steady() -> Result<Self, RclrsError> {
49+
Self::make(ClockType::SteadyTime)
50+
}
51+
52+
/// Creates a new Clock with `ClockType::RosTime` and a matching `ClockSource` that can be used
53+
/// to update it
54+
pub fn with_source() -> Result<(Self, ClockSource), RclrsError> {
55+
let clock = Self::make(ClockType::RosTime)?;
56+
let clock_source = ClockSource {
57+
_rcl_clock: clock._rcl_clock.clone(),
58+
};
59+
Ok((clock, clock_source))
60+
}
61+
3662
/// Creates a new clock of the given `ClockType`.
3763
// TODO(luca) proper error handling
38-
pub fn new(type_: ClockType) -> Result<Self, RclrsError> {
64+
pub fn new(type_: ClockType) -> Result<(Self, Option<ClockSource>), RclrsError> {
65+
let clock = Self::make(type_)?;
66+
let clock_source = if matches!(type_, ClockType::RosTime) {
67+
Some(ClockSource {
68+
_rcl_clock: clock._rcl_clock.clone(),
69+
})
70+
} else {
71+
None
72+
};
73+
Ok((clock, clock_source))
74+
}
75+
76+
// TODO(luca) proper error handling
77+
fn make(type_: ClockType) -> Result<Self, RclrsError> {
3978
let mut rcl_clock;
4079
unsafe {
4180
// SAFETY: Getting a default value is always safe.
@@ -45,34 +84,10 @@ impl Clock {
4584
}
4685
Ok(Self {
4786
_type: type_,
48-
_rcl_clock: Mutex::new(rcl_clock),
87+
_rcl_clock: Arc::new(Mutex::new(rcl_clock)),
4988
})
5089
}
5190

52-
/// Returns the clock's `ClockType`.
53-
pub fn clock_type(&self) -> ClockType {
54-
self._type
55-
}
56-
57-
/// Sets the clock to use ROS Time, if enabled the clock will report the last value set through
58-
/// `Clock::set_ros_time_override(nanoseconds: i64)`.
59-
pub fn set_ros_time(&self, enable: bool) {
60-
let mut clock = self._rcl_clock.lock().unwrap();
61-
if enable {
62-
// SAFETY: Safe if clock jump callbacks are not edited, which is guaranteed
63-
// by the mutex
64-
unsafe {
65-
rcl_enable_ros_time_override(&mut *clock);
66-
}
67-
} else {
68-
// SAFETY: Safe if clock jump callbacks are not edited, which is guaranteed
69-
// by the mutex
70-
unsafe {
71-
rcl_disable_ros_time_override(&mut *clock);
72-
}
73-
}
74-
}
75-
7691
/// Returns the current clock's timestamp.
7792
pub fn now(&self) -> Time {
7893
let mut clock = self._rcl_clock.lock().unwrap();
@@ -87,16 +102,6 @@ impl Clock {
87102
}
88103
}
89104

90-
/// Sets the value of the current ROS time.
91-
pub fn set_ros_time_override(&self, nanoseconds: i64) {
92-
let mut clock = self._rcl_clock.lock().unwrap();
93-
// SAFETY: Safe if clock jump callbacks are not edited, which is guaranteed
94-
// by the mutex
95-
unsafe {
96-
rcl_set_ros_time_override(&mut *clock, nanoseconds);
97-
}
98-
}
99-
100105
/// Helper function to initialize a default clock, same behavior as `rcl_init_generic_clock`.
101106
/// Needed because functions that initialize a clock take as an input a mutable reference
102107
/// to a clock and don't actually return one, so we need a function to generate one. Doing this
@@ -116,6 +121,43 @@ impl Clock {
116121
}
117122
}
118123

124+
impl PartialEq for ClockSource {
125+
fn eq(&self, other: &Self) -> bool {
126+
Arc::ptr_eq(&self._rcl_clock, &other._rcl_clock)
127+
}
128+
}
129+
130+
impl ClockSource {
131+
/// Sets the clock to use ROS Time, if enabled the clock will report the last value set through
132+
/// `Clock::set_ros_time_override(nanoseconds: i64)`.
133+
pub fn set_ros_time_enable(&self, enable: bool) {
134+
let mut clock = self._rcl_clock.lock().unwrap();
135+
if enable {
136+
// SAFETY: Safe if clock jump callbacks are not edited, which is guaranteed
137+
// by the mutex
138+
unsafe {
139+
rcl_enable_ros_time_override(&mut *clock);
140+
}
141+
} else {
142+
// SAFETY: Safe if clock jump callbacks are not edited, which is guaranteed
143+
// by the mutex
144+
unsafe {
145+
rcl_disable_ros_time_override(&mut *clock);
146+
}
147+
}
148+
}
149+
150+
/// Sets the value of the current ROS time.
151+
pub fn set_ros_time_override(&self, nanoseconds: i64) {
152+
let mut clock = self._rcl_clock.lock().unwrap();
153+
// SAFETY: Safe if clock jump callbacks are not edited, which is guaranteed
154+
// by the mutex
155+
unsafe {
156+
rcl_set_ros_time_override(&mut *clock, nanoseconds);
157+
}
158+
}
159+
}
160+
119161
impl Drop for Clock {
120162
fn drop(&mut self) {
121163
// SAFETY: No preconditions for this function
@@ -129,6 +171,7 @@ impl Drop for Clock {
129171
// SAFETY: The functions accessing this type, including drop(), shouldn't care about the thread
130172
// they are running in. Therefore, this type can be safely sent to another thread.
131173
unsafe impl Send for rcl_clock_t {}
174+
unsafe impl Sync for rcl_clock_t {}
132175

133176
#[cfg(test)]
134177
mod tests {
@@ -145,25 +188,25 @@ mod tests {
145188

146189
#[test]
147190
fn clock_system_time_now() {
148-
let clock = Clock::new(ClockType::SystemTime).unwrap();
191+
let clock = Clock::system().unwrap();
149192
assert!(clock.now().nsec > 0);
150193
}
151194

152195
#[test]
153196
fn clock_ros_time_with_override() {
154-
let clock = Clock::new(ClockType::RosTime).unwrap();
197+
let (clock, source) = Clock::with_source().unwrap();
155198
let start = clock.now();
156199
// Ros time is not set, should return wall time
157200
assert!(start.nsec > 0);
158-
clock.set_ros_time(true);
201+
source.set_ros_time_enable(true);
159202
// No manual time set, it should default to 0
160203
assert!(clock.now().nsec == 0);
161204
let set_time = 1234i64;
162-
clock.set_ros_time_override(set_time);
205+
source.set_ros_time_override(set_time);
163206
// Ros time is set, should return the value that was set
164207
assert_eq!(clock.now().nsec, set_time);
165208
// Back to normal time, should be greater than before
166-
clock.set_ros_time(false);
209+
source.set_ros_time_enable(false);
167210
assert!(clock.now().nsec != set_time);
168211
assert!(clock.now().nsec > start.nsec);
169212
}

rclrs/src/lib.rs

Lines changed: 1 addition & 7 deletions
Original file line numberDiff line numberDiff line change
@@ -115,13 +115,7 @@ pub fn spin(node: Arc<Node>) -> Result<(), RclrsError> {
115115
/// # Ok::<(), RclrsError>(())
116116
/// ```
117117
pub fn create_node(context: &Context, node_name: &str) -> Result<Arc<Node>, RclrsError> {
118-
let node = Arc::new(Node::builder(context, node_name).build()?);
119-
*node._time_source.lock().unwrap() = Some(
120-
TimeSourceBuilder::new(node.clone(), node.get_clock())
121-
.build()
122-
.unwrap(),
123-
);
124-
Ok(node)
118+
Node::builder(context, node_name).build()
125119
}
126120

127121
/// Creates a [`NodeBuilder`][1].

rclrs/src/node.rs

Lines changed: 4 additions & 4 deletions
Original file line numberDiff line numberDiff line change
@@ -71,7 +71,7 @@ pub struct Node {
7171
pub(crate) guard_conditions_mtx: Mutex<Vec<Weak<GuardCondition>>>,
7272
pub(crate) services_mtx: Mutex<Vec<Weak<dyn ServiceBase>>>,
7373
pub(crate) subscriptions_mtx: Mutex<Vec<Weak<dyn SubscriptionBase>>>,
74-
_clock: Arc<Clock>,
74+
_clock: Clock,
7575
// TODO(luca) set to private
7676
pub(crate) _time_source: Arc<Mutex<Option<TimeSource>>>,
7777
_parameter_map: ParameterOverrideMap,
@@ -98,13 +98,13 @@ impl Node {
9898
///
9999
/// See [`NodeBuilder::new()`] for documentation.
100100
#[allow(clippy::new_ret_no_self)]
101-
pub fn new(context: &Context, node_name: &str) -> Result<Node, RclrsError> {
101+
pub fn new(context: &Context, node_name: &str) -> Result<Arc<Node>, RclrsError> {
102102
Self::builder(context, node_name).build()
103103
}
104104

105105
/// Gets the clock associated with this node.
106-
pub fn get_clock(&self) -> Arc<Clock> {
107-
self._clock.clone()
106+
pub fn get_clock(&self) -> &Clock {
107+
&self._clock
108108
}
109109

110110
/// Returns the name of the node.

rclrs/src/node/builder.rs

Lines changed: 14 additions & 6 deletions
Original file line numberDiff line numberDiff line change
@@ -4,7 +4,7 @@ use std::sync::{Arc, Mutex};
44
use crate::rcl_bindings::*;
55
use crate::{
66
node::call_string_getter_with_handle, resolve_parameter_overrides, Clock, ClockType, Context,
7-
Node, RclrsError, ToResult,
7+
Node, RclrsError, TimeSourceBuilder, ToResult,
88
};
99

1010
/// A builder for creating a [`Node`][1].
@@ -234,7 +234,7 @@ impl NodeBuilder {
234234
/// For example usage, see the [`NodeBuilder`][1] docs.
235235
///
236236
/// [1]: crate::NodeBuilder
237-
pub fn build(&self) -> Result<Node, RclrsError> {
237+
pub fn build(&self) -> Result<Arc<Node>, RclrsError> {
238238
let node_name =
239239
CString::new(self.name.as_str()).map_err(|err| RclrsError::StringContainsNul {
240240
err,
@@ -265,7 +265,7 @@ impl NodeBuilder {
265265
.ok()?;
266266
};
267267

268-
let clock = Clock::new(self.clock_type)?;
268+
let (clock, clock_source) = Clock::new(self.clock_type)?;
269269

270270
let _parameter_map = unsafe {
271271
let fqn = call_string_getter_with_handle(&rcl_node, rcl_node_get_fully_qualified_name);
@@ -276,17 +276,25 @@ impl NodeBuilder {
276276
)?
277277
};
278278
let rcl_node_mtx = Arc::new(Mutex::new(rcl_node));
279-
let node = Node {
279+
let node = Arc::new(Node {
280280
rcl_node_mtx,
281281
rcl_context_mtx: self.context.clone(),
282282
clients_mtx: Mutex::new(vec![]),
283283
guard_conditions_mtx: Mutex::new(vec![]),
284284
services_mtx: Mutex::new(vec![]),
285285
subscriptions_mtx: Mutex::new(vec![]),
286-
_clock: Arc::new(clock),
286+
_clock: clock,
287287
_time_source: Arc::new(Mutex::new(None)),
288288
_parameter_map,
289-
};
289+
});
290+
291+
if let Some(clock_source) = clock_source {
292+
*node._time_source.lock().unwrap() = Some(
293+
TimeSourceBuilder::new(node.clone(), clock_source)
294+
.build()
295+
.unwrap(),
296+
);
297+
}
290298

291299
Ok(node)
292300
}

0 commit comments

Comments
 (0)