Skip to content

Commit

Permalink
Change get_clock() to return cloned Clock object
Browse files Browse the repository at this point in the history
Signed-off-by: Luca Della Vedova <lucadv@intrinsic.ai>
  • Loading branch information
luca-della-vedova committed Sep 13, 2023
1 parent edce20e commit 632e082
Show file tree
Hide file tree
Showing 4 changed files with 11 additions and 10 deletions.
2 changes: 1 addition & 1 deletion examples/minimal_pub_sub/src/minimal_subscriber.rs
Original file line number Diff line number Diff line change
Expand Up @@ -17,7 +17,7 @@ fn main() -> Result<(), Error> {
num_messages += 1;
println!("I heard: '{}'", msg.data);
println!("(Got {} messages so far)", num_messages);
let now = inner_node.get_clock().lock().unwrap().now();
let now = inner_node.get_clock().now();
dbg!(now);
},
)?;
Expand Down
1 change: 1 addition & 0 deletions rclrs/src/clock.rs
Original file line number Diff line number Diff line change
Expand Up @@ -26,6 +26,7 @@ impl From<ClockType> for rcl_clock_type_t {
}

/// Struct that implements a Clock and wraps `rcl_clock_t`.
#[derive(Clone, Debug)]
pub struct Clock {
_type: ClockType,
_rcl_clock: Arc<Mutex<rcl_clock_t>>,
Expand Down
4 changes: 2 additions & 2 deletions rclrs/src/node.rs
Original file line number Diff line number Diff line change
Expand Up @@ -100,8 +100,8 @@ impl Node {
Self::builder(context, node_name).build()
}

/// Gets the clock associated with this node.
pub fn get_clock(&self) -> Arc<Mutex<Clock>> {
/// Returns the clock associated with this node.
pub fn get_clock(&self) -> Clock {
self._time_source.get_clock()
}

Expand Down
14 changes: 7 additions & 7 deletions rclrs/src/time_source.rs
Original file line number Diff line number Diff line change
@@ -1,14 +1,14 @@
use crate::clock::{Clock, ClockSource, ClockType};
use crate::{Node, ParameterValue, QoSProfile, RclrsError, Subscription, QOS_PROFILE_CLOCK};
use rosgraph_msgs::msg::Clock as ClockMsg;
use std::sync::{Arc, Mutex, Weak};
use std::sync::{Arc, Mutex, RwLock, Weak};

/// Time source for a node that drives the attached clock.
/// If the node's `use_sim_time` parameter is set to `true`, the `TimeSource` will subscribe
/// to the `/clock` topic and drive the attached clock
pub struct TimeSource {
_node: Weak<Node>,
_clock: Arc<Mutex<Clock>>,
_clock: RwLock<Clock>,
_clock_source: Arc<Mutex<Option<ClockSource>>>,
_requested_clock_type: ClockType,
_clock_qos: QoSProfile,
Expand Down Expand Up @@ -72,7 +72,7 @@ impl TimeSourceBuilder {
}?;
let mut source = TimeSource {
_node: Weak::new(),
_clock: Arc::new(Mutex::new(clock)),
_clock: RwLock::new(clock),
_clock_source: Arc::new(Mutex::new(None)),
_requested_clock_type: self.clock_type,
_clock_qos: self.clock_qos,
Expand All @@ -97,8 +97,8 @@ impl TimeSource {
}

/// Returns the clock that this TimeSource is controlling.
pub fn get_clock(&self) -> Arc<Mutex<Clock>> {
self._clock.clone()
pub fn get_clock(&self) -> Clock {
self._clock.read().unwrap().clone()
}

/// Attaches the given node to to the `TimeSource`, using its interface to read the
Expand All @@ -123,7 +123,7 @@ impl TimeSource {

fn set_ros_time_enable(&mut self, enable: bool) {
if matches!(self._requested_clock_type, ClockType::RosTime) {
let mut clock = self._clock.lock().unwrap();
let mut clock = self._clock.write().unwrap();
if enable && matches!(clock.clock_type(), ClockType::SystemTime) {
// TODO(luca) remove unwrap here?
let (new_clock, mut clock_source) = Clock::with_source().unwrap();
Expand Down Expand Up @@ -174,7 +174,7 @@ mod tests {
fn time_source_attach_clock() {
let node = create_node(&Context::new([]).unwrap(), "test_node").unwrap();
// Default clock should be above 0 (use_sim_time is default false)
assert!(node.get_clock().lock().unwrap().now().nsec > 0);
assert!(node.get_clock().now().nsec > 0);
// TODO(luca) an integration test by creating a node and setting its use_sim_time
}
}

0 comments on commit 632e082

Please sign in to comment.