diff --git a/examples/minimal_pub_sub/src/minimal_two_nodes.rs b/examples/minimal_pub_sub/src/minimal_two_nodes.rs index ff74e9902..46bd9780c 100644 --- a/examples/minimal_pub_sub/src/minimal_two_nodes.rs +++ b/examples/minimal_pub_sub/src/minimal_two_nodes.rs @@ -7,8 +7,8 @@ use anyhow::{Error, Result}; struct MinimalSubscriber { num_messages: AtomicU32, - node: Arc, - subscription: Mutex>>>, + node: rclrs::Node, + subscription: Mutex>>, } impl MinimalSubscriber { diff --git a/examples/rust_pubsub/src/simple_publisher.rs b/examples/rust_pubsub/src/simple_publisher.rs index 24fdb683b..b4283d073 100644 --- a/examples/rust_pubsub/src/simple_publisher.rs +++ b/examples/rust_pubsub/src/simple_publisher.rs @@ -3,7 +3,7 @@ use std::{sync::Arc, thread, time::Duration}; use std_msgs::msg::String as StringMsg; struct SimplePublisherNode { - publisher: Arc>, + publisher: Publisher, } impl SimplePublisherNode { @@ -26,12 +26,11 @@ impl SimplePublisherNode { fn main() -> Result<(), RclrsError> { let mut executor = Context::default_from_env().unwrap().create_basic_executor(); - let publisher = Arc::new(SimplePublisher::new(&executor).unwrap()); - let publisher_other_thread = Arc::clone(&publisher); + let node = Arc::new(SimplePublisher::new(&executor).unwrap()); let mut count: i32 = 0; thread::spawn(move || loop { thread::sleep(Duration::from_millis(1000)); - count = publisher_other_thread.publish_data(count).unwrap(); + count = node.publish_data(count).unwrap(); }); executor.spin(SpinOptions::default()) } diff --git a/examples/rust_pubsub/src/simple_subscriber.rs b/examples/rust_pubsub/src/simple_subscriber.rs index 2b283379f..bae5f551b 100644 --- a/examples/rust_pubsub/src/simple_subscriber.rs +++ b/examples/rust_pubsub/src/simple_subscriber.rs @@ -37,11 +37,10 @@ impl SimpleSubscriptionNode { } fn main() -> Result<(), RclrsError> { let mut executor = Context::default_from_env().unwrap().create_basic_executor(); - let subscription = Arc::new(SimpleSubscriptionNode::new(&executor).unwrap()); - let subscription_other_thread = Arc::clone(&subscription); + let node = Arc::new(SimpleSubscriptionNode::new(&executor).unwrap()); thread::spawn(move || loop { thread::sleep(Duration::from_millis(1000)); - subscription_other_thread.data_callback().unwrap() + node.data_callback().unwrap() }); executor.spin(SpinOptions::default()) } diff --git a/rclrs/src/client.rs b/rclrs/src/client.rs index 8ee356e9a..72de8cfe1 100644 --- a/rclrs/src/client.rs +++ b/rclrs/src/client.rs @@ -1,7 +1,7 @@ use std::{ collections::HashMap, ffi::CString, - sync::{Arc, Mutex, MutexGuard}, + sync::{atomic::AtomicBool, Arc, Mutex, MutexGuard}, }; use rosidl_runtime_rs::Message; @@ -23,12 +23,25 @@ pub use client_output::*; /// Main class responsible for sending requests to a ROS service. /// -/// The only available way to instantiate clients is via [`Node::create_client`][1], this is to -/// ensure that [`Node`][2]s can track all the clients that have been created. +/// Create a client using [`Node::create_client`][1]. /// -/// [1]: crate::Node::create_client -/// [2]: crate::Node -pub struct Client +/// Receiving responses requires the node's executor to [spin][2]. +/// +/// [1]: crate::NodeState::create_client +/// [2]: crate::spin +pub type Client = Arc>; + +/// The inner state of a [`Client`]. +/// +/// This is public so that you can choose to create a [`Weak`][1] reference to it +/// if you want to be able to refer to a [`Client`] in a non-owning way. It is +/// generally recommended to manage the `ClientState` inside of an [`Arc`], +/// and [`Client`] is provided as a convenience alias for that. +/// +/// The public API of the [`Client`] type is implemented via `ClientState`. +/// +/// [1]: std::sync::Weak +pub struct ClientState where T: rosidl_runtime_rs::Service, { @@ -38,7 +51,7 @@ where lifecycle: WaitableLifecycle, } -impl Client +impl ClientState where T: rosidl_runtime_rs::Service, { @@ -171,7 +184,7 @@ where /// Creates a new client. pub(crate) fn create<'a>( - node: &Arc, + node: &Node, options: impl Into>, ) -> Result, RclrsError> // This uses pub(crate) visibility to avoid instantiating this struct outside @@ -407,7 +420,7 @@ struct ClientHandle { rcl_client: Mutex, /// We store the whole node here because we use some of its user-facing API /// in some of the Client methods. - node: Arc, + node: Node, } impl ClientHandle { diff --git a/rclrs/src/executor.rs b/rclrs/src/executor.rs index 430fa4168..07b1c90bb 100644 --- a/rclrs/src/executor.rs +++ b/rclrs/src/executor.rs @@ -34,7 +34,7 @@ impl Executor { pub fn create_node<'a>( &'a self, options: impl IntoNodeOptions<'a>, - ) -> Result, RclrsError> { + ) -> Result { let options = options.into_node_options(); let node = options.build(&self.commands)?; Ok(node) @@ -128,7 +128,7 @@ impl ExecutorCommands { pub fn create_node<'a>( self: &Arc, options: impl IntoNodeOptions<'a>, - ) -> Result, RclrsError> { + ) -> Result { let options = options.into_node_options(); options.build(self) } diff --git a/rclrs/src/node.rs b/rclrs/src/node.rs index 41fba947a..f544575d6 100644 --- a/rclrs/src/node.rs +++ b/rclrs/src/node.rs @@ -29,11 +29,12 @@ use async_std::future::timeout; use rosidl_runtime_rs::Message; use crate::{ - rcl_bindings::*, Client, ClientOptions, Clock, ContextHandle, ExecutorCommands, LogParams, - Logger, ParameterBuilder, ParameterInterface, ParameterVariant, Parameters, Promise, Publisher, - PublisherOptions, QoSProfile, RclrsError, Service, ServiceAsyncCallback, ServiceCallback, - ServiceOptions, Subscription, SubscriptionAsyncCallback, SubscriptionCallback, - SubscriptionOptions, TimeSource, ToLogParams, ENTITY_LIFECYCLE_MUTEX, + rcl_bindings::*, Client, ClientOptions, ClientState, Clock, ContextHandle, ExecutorCommands, + LogParams, Logger, ParameterBuilder, ParameterInterface, ParameterVariant, Parameters, Promise, + Publisher, PublisherOptions, PublisherState, QoSProfile, RclrsError, Service, + ServiceAsyncCallback, ServiceCallback, ServiceOptions, ServiceState, Subscription, + SubscriptionAsyncCallback, SubscriptionCallback, SubscriptionOptions, SubscriptionState, + TimeSource, ToLogParams, ENTITY_LIFECYCLE_MUTEX, }; /// A processing unit that can communicate with other nodes. @@ -78,7 +79,19 @@ use crate::{ /// [5]: crate::NodeOptions::new /// [6]: crate::NodeOptions::namespace /// [7]: crate::Executor::create_node -pub struct Node { + +pub type Node = Arc; + +/// The inner state of a [`Node`]. +/// +/// This is public so that you can choose to put it inside a [`Weak`] if you +/// want to be able to refer to a [`Node`] in a non-owning way. It is generally +/// recommended to manage the [`NodeState`] inside of an [`Arc`], and [`Node`] +/// recommended to manage the `NodeState` inside of an [`Arc`], and [`Node`] +/// is provided as convenience alias for that. +/// +/// The public API of the [`Node`] type is implemented via `NodeState`. +pub struct NodeState { time_source: TimeSource, parameter: ParameterInterface, logger: Logger, @@ -132,15 +145,15 @@ impl Drop for NodeHandle { } } -impl Eq for Node {} +impl Eq for NodeState {} -impl PartialEq for Node { +impl PartialEq for NodeState { fn eq(&self, other: &Self) -> bool { Arc::ptr_eq(&self.handle, &other.handle) } } -impl fmt::Debug for Node { +impl fmt::Debug for NodeState { fn fmt(&self, f: &mut fmt::Formatter<'_>) -> Result<(), fmt::Error> { f.debug_struct("Node") .field("fully_qualified_name", &self.fully_qualified_name()) @@ -148,7 +161,7 @@ impl fmt::Debug for Node { } } -impl Node { +impl NodeState { /// Returns the clock associated with this node. pub fn get_clock(&self) -> Clock { self.time_source.get_clock() @@ -206,7 +219,7 @@ impl Node { /// Returns the fully qualified name of the node. /// /// The fully qualified name of the node is the node namespace combined with the node name. - /// It is subject to the remappings shown in [`Node::name()`] and [`Node::namespace()`]. + /// It is subject to the remappings shown in [`NodeState::name()`] and [`NodeState::namespace()`]. /// /// # Example /// ``` @@ -261,11 +274,11 @@ impl Node { pub fn create_client<'a, T>( self: &Arc, options: impl Into>, - ) -> Result>, RclrsError> + ) -> Result, RclrsError> where T: rosidl_runtime_rs::Service, { - Client::::create(self, options) + ClientState::::create(self, options) } /// Creates a [`Publisher`][1]. @@ -305,11 +318,11 @@ impl Node { pub fn create_publisher<'a, T>( &self, options: impl Into>, - ) -> Result>, RclrsError> + ) -> Result, RclrsError> where T: Message, { - Publisher::::create(Arc::clone(&self.handle), options) + PublisherState::::create(Arc::clone(&self.handle), options) } /// Creates a [`Service`] with an ordinary callback. @@ -373,11 +386,11 @@ impl Node { &self, options: impl Into>, callback: impl ServiceCallback, - ) -> Result>, RclrsError> + ) -> Result, RclrsError> where T: rosidl_runtime_rs::Service, { - Service::::create( + ServiceState::::create( options, callback.into_service_callback(), &self.handle, @@ -408,11 +421,11 @@ impl Node { &self, options: impl Into>, callback: impl ServiceAsyncCallback, - ) -> Result>, RclrsError> + ) -> Result, RclrsError> where T: rosidl_runtime_rs::Service, { - Service::::create( + ServiceState::::create( options, callback.into_service_async_callback(), &self.handle, @@ -480,11 +493,11 @@ impl Node { &self, options: impl Into>, callback: impl SubscriptionCallback, - ) -> Result>, RclrsError> + ) -> Result, RclrsError> where T: Message, { - Subscription::::create( + SubscriptionState::::create( options, callback.into_subscription_callback(), &self.handle, @@ -515,11 +528,11 @@ impl Node { &self, options: impl Into>, callback: impl SubscriptionAsyncCallback, - ) -> Result>, RclrsError> + ) -> Result, RclrsError> where T: Message, { - Subscription::::create( + SubscriptionState::::create( options, callback.into_subscription_async_callback(), &self.handle, @@ -689,7 +702,7 @@ impl Node { } } -impl<'a> ToLogParams<'a> for &'a Node { +impl<'a> ToLogParams<'a> for &'a NodeState { fn to_log_params(self) -> LogParams<'a> { self.logger().to_log_params() } diff --git a/rclrs/src/node/graph.rs b/rclrs/src/node/graph.rs index 870b2b67a..948d55621 100644 --- a/rclrs/src/node/graph.rs +++ b/rclrs/src/node/graph.rs @@ -3,7 +3,7 @@ use std::{ ffi::{CStr, CString}, }; -use crate::{rcl_bindings::*, Node, RclrsError, ToResult}; +use crate::{rcl_bindings::*, NodeState, RclrsError, ToResult}; impl Drop for rmw_names_and_types_t { fn drop(&mut self) { @@ -57,7 +57,7 @@ pub struct TopicEndpointInfo { pub topic_type: String, } -impl Node { +impl NodeState { /// Returns a list of topic names and types for publishers associated with a node. pub fn get_publisher_names_and_types_by_node( &self, diff --git a/rclrs/src/node/node_options.rs b/rclrs/src/node/node_options.rs index f0ffdf0c0..08f6bebbf 100644 --- a/rclrs/src/node/node_options.rs +++ b/rclrs/src/node/node_options.rs @@ -9,8 +9,9 @@ use futures::channel::mpsc::unbounded; use crate::{ node::node_graph_task::{node_graph_task, NodeGraphAction}, rcl_bindings::*, - ClockType, ExecutorCommands, GuardCondition, Logger, Node, NodeHandle, ParameterInterface, - QoSProfile, RclrsError, TimeSource, ToResult, ENTITY_LIFECYCLE_MUTEX, QOS_PROFILE_CLOCK, + ClockType, ExecutorCommands, GuardCondition, Logger, Node, NodeHandle, NodeState, + ParameterInterface, QoSProfile, RclrsError, TimeSource, ToResult, ENTITY_LIFECYCLE_MUTEX, + QOS_PROFILE_CLOCK, }; /// This trait helps to build [`NodeOptions`] which can be passed into @@ -289,7 +290,7 @@ impl<'a> NodeOptions<'a> { /// /// Only used internally. Downstream users should call /// [`Executor::create_node`]. - pub(crate) fn build(self, commands: &Arc) -> Result, RclrsError> { + pub(crate) fn build(self, commands: &Arc) -> Result { let node_name = CString::new(self.name).map_err(|err| RclrsError::StringContainsNul { err, s: self.name.to_owned(), @@ -388,7 +389,7 @@ impl<'a> NodeOptions<'a> { graph_change_guard_condition, )); - let node = Arc::new(Node { + let node = Arc::new(NodeState { time_source: TimeSource::builder(self.clock_type) .clock_qos(self.clock_qos) .build(), diff --git a/rclrs/src/parameter.rs b/rclrs/src/parameter.rs index 44ca7365c..2a6913a5f 100644 --- a/rclrs/src/parameter.rs +++ b/rclrs/src/parameter.rs @@ -84,7 +84,7 @@ enum DeclaredValue { } /// Builder used to declare a parameter. Obtain this by calling -/// [`crate::Node::declare_parameter`]. +/// [`crate::NodeState::declare_parameter`]. #[must_use] pub struct ParameterBuilder<'a, T: ParameterVariant> { name: Arc, diff --git a/rclrs/src/parameter/service.rs b/rclrs/src/parameter/service.rs index 0930d1bd3..3bffa5cf7 100644 --- a/rclrs/src/parameter/service.rs +++ b/rclrs/src/parameter/service.rs @@ -16,17 +16,17 @@ use crate::{ // What is used is the Weak that is stored in the node, and is upgraded when spinning. pub struct ParameterService { #[allow(dead_code)] - describe_parameters_service: Arc>, + describe_parameters_service: Service, #[allow(dead_code)] - get_parameter_types_service: Arc>, + get_parameter_types_service: Service, #[allow(dead_code)] - get_parameters_service: Arc>, + get_parameters_service: Service, #[allow(dead_code)] - list_parameters_service: Arc>, + list_parameters_service: Service, #[allow(dead_code)] - set_parameters_service: Arc>, + set_parameters_service: Service, #[allow(dead_code)] - set_parameters_atomically_service: Arc>, + set_parameters_atomically_service: Service, } fn describe_parameters( @@ -314,7 +314,7 @@ mod tests { srv::rmw::*, }, Context, Executor, IntoNodeOptions, MandatoryParameter, Node, NodeOptions, ParameterRange, - ParameterValue, QoSProfile, RclrsError, ReadOnlyParameter, SpinOptions, + ParameterValue, RclrsError, ReadOnlyParameter, SpinOptions, }; use rosidl_runtime_rs::{seq, Sequence}; use std::{ @@ -326,14 +326,14 @@ mod tests { }; struct TestNode { - node: Arc, + node: Node, bool_param: MandatoryParameter, _ns_param: MandatoryParameter, _read_only_param: ReadOnlyParameter, dynamic_param: MandatoryParameter, } - fn construct_test_nodes(ns: &str) -> (Executor, TestNode, Arc) { + fn construct_test_nodes(ns: &str) -> (Executor, TestNode, Node) { let executor = Context::default().create_basic_executor(); let node = executor .create_node(NodeOptions::new("node").namespace(ns)) diff --git a/rclrs/src/publisher.rs b/rclrs/src/publisher.rs index 4cb1095ef..967cb9c62 100644 --- a/rclrs/src/publisher.rs +++ b/rclrs/src/publisher.rs @@ -45,15 +45,32 @@ impl Drop for PublisherHandle { /// Struct for sending messages of type `T`. /// +/// Create a publisher using [`Node::create_publisher`][1]. +/// /// Multiple publishers can be created for the same topic, in different nodes or the same node. +/// A clone of a `Publisher` will refer to the same publisher instance as the original. +/// The underlying instance is tied to [`PublisherState`] which implements the [`Publisher`] API. /// /// The underlying RMW will decide on the concrete delivery mechanism (network stack, shared /// memory, or intraprocess). /// /// Sending messages does not require the node's executor to [spin][2]. /// +/// [1]: crate::NodeState::create_publisher /// [2]: crate::Executor::spin -pub struct Publisher +pub type Publisher = Arc>; + +/// The inner state of a [`Publisher`]. +/// +/// This is public so that you can choose to create a [`Weak`][1] reference to it +/// if you want to be able to refer to a [`Publisher`] in a non-owning way. It is +/// generally recommended to manage the `PublisherState` inside of an [`Arc`], +/// and [`Publisher`] is provided as a convenience alias for that. +/// +/// The public API of the [`Publisher`] type is implemented via `PublisherState`. +/// +/// [1]: std::sync::Weak +pub struct PublisherState where T: Message, { @@ -66,12 +83,12 @@ where // SAFETY: The functions accessing this type, including drop(), shouldn't care about the thread // they are running in. Therefore, this type can be safely sent to another thread. -unsafe impl Send for Publisher where T: Message {} +unsafe impl Send for PublisherState where T: Message {} // SAFETY: The type_support_ptr prevents the default Sync impl. // rosidl_message_type_support_t is a read-only type without interior mutability. -unsafe impl Sync for Publisher where T: Message {} +unsafe impl Sync for PublisherState where T: Message {} -impl Publisher +impl PublisherState where T: Message, { @@ -179,7 +196,7 @@ where } } -impl Publisher +impl PublisherState where T: RmwMessage, { @@ -268,7 +285,7 @@ impl<'a, T: IntoPrimitiveOptions<'a>> From for PublisherOptions<'a> { } } -/// Convenience trait for [`Publisher::publish`]. +/// Convenience trait for [`PublisherState::publish`]. pub trait MessageCow<'a, T: Message> { /// Wrap the owned or borrowed message in a `Cow`. fn into_cow(self) -> Cow<'a, T>; diff --git a/rclrs/src/publisher/loaned_message.rs b/rclrs/src/publisher/loaned_message.rs index 7d29122dc..924e7d21e 100644 --- a/rclrs/src/publisher/loaned_message.rs +++ b/rclrs/src/publisher/loaned_message.rs @@ -2,13 +2,13 @@ use std::ops::{Deref, DerefMut}; use rosidl_runtime_rs::RmwMessage; -use crate::{rcl_bindings::*, Publisher, RclrsError, ToResult}; +use crate::{rcl_bindings::*, PublisherState, RclrsError, ToResult}; /// A message that is owned by the middleware, loaned for publishing. /// /// It dereferences to a `&mut T`. /// -/// This type is returned by [`Publisher::borrow_loaned_message()`], see the documentation of +/// This type is returned by [`PublisherState::borrow_loaned_message()`], see the documentation of /// that function for more information. /// /// The loan is returned by dropping the message or [publishing it][1]. @@ -19,7 +19,7 @@ where T: RmwMessage, { pub(super) msg_ptr: *mut T, - pub(super) publisher: &'a Publisher, + pub(super) publisher: &'a PublisherState, } impl Deref for LoanedMessage<'_, T> diff --git a/rclrs/src/service.rs b/rclrs/src/service.rs index d794f0876..87d5a0fcd 100644 --- a/rclrs/src/service.rs +++ b/rclrs/src/service.rs @@ -24,18 +24,36 @@ pub use service_callback::*; mod service_info; pub use service_info::*; -/// Struct for responding to requests sent by ROS service clients. +/// Provide a service that can respond to requests sent by ROS service clients. /// -/// The only way to instantiate a service is via [`Node::create_service()`][1] +/// Create a service using [`Node::create_service`][1] /// or [`Node::create_async_service`][2]. /// -/// Services should be unique per service name (including namespace) throughout -/// an entire ROS system. ROS does not currently support multiple services that -/// use the same name (including namespace). +/// ROS only supports having one service provider for any given fully-qualified +/// service name. "Fully-qualified" means the namespace is also taken into account +/// for uniqueness. A clone of a `Service` will refer to the same service provider +/// instance as the original. The underlying instance is tied to [`ServiceState`] +/// which implements the [`Service`] API. +/// +/// Responding to requests requires the node's executor to [spin][3]. /// /// [1]: crate::Node::create_service /// [2]: crate::Node::create_async_service -pub struct Service +/// [3]: crate::Executor::spin +/// +pub type Service = Arc>; + +/// The inner state of a [`Service`]. +/// +/// This is public so that you can choose to create a [`Weak`][1] reference to it +/// if you want to be able to refer to a [`Service`] in a non-owning way. It is +/// generally recommended to manage the `ServiceState` inside of an [`Arc`], +/// and [`Service`] is provided as a convenience alias for that. +/// +/// The public API of the [`Service`] type is implemented via `ServiceState`. +/// +/// [1]: std::sync::Weak +pub struct ServiceState where T: rosidl_runtime_rs::Service, { @@ -49,7 +67,7 @@ where lifecycle: WaitableLifecycle, } -impl Service +impl ServiceState where T: rosidl_runtime_rs::Service, { diff --git a/rclrs/src/subscription.rs b/rclrs/src/subscription.rs index f5a76a1f3..9d639acbb 100644 --- a/rclrs/src/subscription.rs +++ b/rclrs/src/subscription.rs @@ -28,10 +28,12 @@ pub use readonly_loaned_message::*; /// Struct for receiving messages of type `T`. /// -/// The only way to instantiate a subscription is via [`Node::create_subscription()`][2] +/// Create a subscription using [`Node::create_subscription()`][2] /// or [`Node::create_async_subscription`][3]. /// /// There can be multiple subscriptions for the same topic, in different nodes or the same node. +/// A clone of a `Subscription` will refer to the same subscription instance as the original. +/// The underlying instance is tied to [`SubscriptionState`] which implements the [`Subscription`] API. /// /// Receiving messages requires calling [`spin`][1] on the `Executor` of subscription's [Node][4]. /// @@ -42,7 +44,19 @@ pub use readonly_loaned_message::*; /// [2]: crate::Node::create_subscription /// [3]: crate::Node::create_async_subscription /// [4]: crate::Node -pub struct Subscription +pub type Subscription = Arc>; + +/// The inner state of a [`Subscription`]. +/// +/// This is public so that you can choose to create a [`Weak`][1] reference to it +/// if you want to be able to refer to a [`Subscription`] in a non-owning way. It is +/// generally recommended to manage the `SubscriptionState` inside of an [`Arc`], +/// and [`Subscription`] is provided as a convenience alias for that. +/// +/// The public API of the [`Subscription`] type is implemented via `SubscriptionState`. +/// +/// [1]: std::sync::Weak +pub struct SubscriptionState where T: Message, { @@ -59,7 +73,7 @@ where lifecycle: WaitableLifecycle, } -impl Subscription +impl SubscriptionState where T: Message, { @@ -262,8 +276,8 @@ mod tests { #[test] fn traits() { - assert_send::>(); - assert_sync::>(); + assert_send::>(); + assert_sync::>(); } #[test] diff --git a/rclrs/src/test_helpers/graph_helpers.rs b/rclrs/src/test_helpers/graph_helpers.rs index ece87372a..9aa93bf0c 100644 --- a/rclrs/src/test_helpers/graph_helpers.rs +++ b/rclrs/src/test_helpers/graph_helpers.rs @@ -2,8 +2,8 @@ use crate::{Context, IntoNodeOptions, Node, RclrsError}; use std::sync::Arc; pub(crate) struct TestGraph { - pub node1: Arc, - pub node2: Arc, + pub node1: Node, + pub node2: Node, } pub(crate) fn construct_test_graph(namespace: &str) -> Result { diff --git a/rclrs/src/time_source.rs b/rclrs/src/time_source.rs index 401f6de98..d8165b937 100644 --- a/rclrs/src/time_source.rs +++ b/rclrs/src/time_source.rs @@ -1,7 +1,8 @@ use crate::{ clock::{Clock, ClockSource, ClockType}, vendor::rosgraph_msgs::msg::Clock as ClockMsg, - IntoPrimitiveOptions, Node, QoSProfile, ReadOnlyParameter, Subscription, QOS_PROFILE_CLOCK, + IntoPrimitiveOptions, Node, NodeState, QoSProfile, ReadOnlyParameter, Subscription, + QOS_PROFILE_CLOCK, }; use std::sync::{Arc, Mutex, RwLock, Weak}; @@ -9,12 +10,12 @@ use std::sync::{Arc, Mutex, RwLock, Weak}; /// 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(crate) struct TimeSource { - node: Mutex>, + node: Mutex>, clock: RwLock, clock_source: Arc>>, requested_clock_type: ClockType, clock_qos: QoSProfile, - clock_subscription: Mutex>>>, + clock_subscription: Mutex>>, last_received_time: Arc>>, // TODO(luca) Make this parameter editable when we have parameter callbacks implemented and can // safely change clock type at runtime @@ -85,7 +86,7 @@ impl TimeSource { /// Attaches the given node to to the `TimeSource`, using its interface to read the /// `use_sim_time` parameter and create the clock subscription. - pub(crate) fn attach_node(&self, node: &Arc) { + pub(crate) fn attach_node(&self, node: &Node) { // TODO(luca) Make this parameter editable and register a parameter callback // that calls set_ros_time(bool) once parameter callbacks are implemented. let param = node @@ -122,7 +123,7 @@ impl TimeSource { clock.set_ros_time_override(nanoseconds); } - fn create_clock_sub(&self) -> Arc> { + fn create_clock_sub(&self) -> Subscription { let clock = self.clock_source.clone(); let last_received_time = self.last_received_time.clone(); // Safe to unwrap since the function will only fail if invalid arguments are provided