1
1
use crate :: rcl_bindings:: * ;
2
2
use crate :: { error:: ToResult , time:: Time , to_rclrs_result, RclrsError } ;
3
- use std:: sync:: Mutex ;
3
+ use std:: sync:: { Arc , Mutex } ;
4
4
5
5
/// Enum to describe clock type. Redefined for readability and to eliminate the uninitialized case
6
6
/// from the `rcl_clock_type_t` enum in the binding.
@@ -28,14 +28,53 @@ impl From<ClockType> for rcl_clock_type_t {
28
28
/// Struct that implements a Clock and wraps `rcl_clock_t`.
29
29
pub struct Clock {
30
30
_type : ClockType ,
31
- _rcl_clock : Mutex < rcl_clock_t > ,
31
+ _rcl_clock : Arc < Mutex < rcl_clock_t > > ,
32
32
// TODO(luca) Implement jump callbacks
33
33
}
34
34
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
+
35
41
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
+
36
62
/// Creates a new clock of the given `ClockType`.
37
63
// 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 > {
39
78
let mut rcl_clock;
40
79
unsafe {
41
80
// SAFETY: Getting a default value is always safe.
@@ -45,34 +84,10 @@ impl Clock {
45
84
}
46
85
Ok ( Self {
47
86
_type : type_,
48
- _rcl_clock : Mutex :: new ( rcl_clock) ,
87
+ _rcl_clock : Arc :: new ( Mutex :: new ( rcl_clock) ) ,
49
88
} )
50
89
}
51
90
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
-
76
91
/// Returns the current clock's timestamp.
77
92
pub fn now ( & self ) -> Time {
78
93
let mut clock = self . _rcl_clock . lock ( ) . unwrap ( ) ;
@@ -87,16 +102,6 @@ impl Clock {
87
102
}
88
103
}
89
104
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
-
100
105
/// Helper function to initialize a default clock, same behavior as `rcl_init_generic_clock`.
101
106
/// Needed because functions that initialize a clock take as an input a mutable reference
102
107
/// 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 {
116
121
}
117
122
}
118
123
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
+
119
161
impl Drop for Clock {
120
162
fn drop ( & mut self ) {
121
163
// SAFETY: No preconditions for this function
@@ -129,6 +171,7 @@ impl Drop for Clock {
129
171
// SAFETY: The functions accessing this type, including drop(), shouldn't care about the thread
130
172
// they are running in. Therefore, this type can be safely sent to another thread.
131
173
unsafe impl Send for rcl_clock_t { }
174
+ unsafe impl Sync for rcl_clock_t { }
132
175
133
176
#[ cfg( test) ]
134
177
mod tests {
@@ -145,25 +188,25 @@ mod tests {
145
188
146
189
#[ test]
147
190
fn clock_system_time_now ( ) {
148
- let clock = Clock :: new ( ClockType :: SystemTime ) . unwrap ( ) ;
191
+ let clock = Clock :: system ( ) . unwrap ( ) ;
149
192
assert ! ( clock. now( ) . nsec > 0 ) ;
150
193
}
151
194
152
195
#[ test]
153
196
fn clock_ros_time_with_override ( ) {
154
- let clock = Clock :: new ( ClockType :: RosTime ) . unwrap ( ) ;
197
+ let ( clock, source ) = Clock :: with_source ( ) . unwrap ( ) ;
155
198
let start = clock. now ( ) ;
156
199
// Ros time is not set, should return wall time
157
200
assert ! ( start. nsec > 0 ) ;
158
- clock . set_ros_time ( true ) ;
201
+ source . set_ros_time_enable ( true ) ;
159
202
// No manual time set, it should default to 0
160
203
assert ! ( clock. now( ) . nsec == 0 ) ;
161
204
let set_time = 1234i64 ;
162
- clock . set_ros_time_override ( set_time) ;
205
+ source . set_ros_time_override ( set_time) ;
163
206
// Ros time is set, should return the value that was set
164
207
assert_eq ! ( clock. now( ) . nsec, set_time) ;
165
208
// Back to normal time, should be greater than before
166
- clock . set_ros_time ( false ) ;
209
+ source . set_ros_time_enable ( false ) ;
167
210
assert ! ( clock. now( ) . nsec != set_time) ;
168
211
assert ! ( clock. now( ) . nsec > start. nsec) ;
169
212
}
0 commit comments