diff --git a/examples/minimal_pub_sub/src/minimal_two_nodes.rs b/examples/minimal_pub_sub/src/minimal_two_nodes.rs index 7c25f3137..968d14d1f 100644 --- a/examples/minimal_pub_sub/src/minimal_two_nodes.rs +++ b/examples/minimal_pub_sub/src/minimal_two_nodes.rs @@ -8,8 +8,8 @@ use anyhow::{Error, Result}; struct MinimalSubscriber { num_messages: AtomicU32, - node: Arc, - subscription: Mutex>>>, + node: Node, + subscription: Mutex>>, } impl MinimalSubscriber { diff --git a/examples/rust_pubsub/src/simple_publisher.rs b/examples/rust_pubsub/src/simple_publisher.rs index ae599c0b5..2428cbb12 100644 --- a/examples/rust_pubsub/src/simple_publisher.rs +++ b/examples/rust_pubsub/src/simple_publisher.rs @@ -1,9 +1,9 @@ use rclrs::*; -use std::{sync::Arc, thread, time::Duration}; +use std::{thread, time::Duration}; use std_msgs::msg::String as StringMsg; struct SimplePublisher { - publisher: Arc>, + publisher: Publisher, } impl SimplePublisher { @@ -24,12 +24,11 @@ impl SimplePublisher { 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 publisher = 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 = publisher.publish_data(count).unwrap(); }); executor.spin(SpinOptions::default()).first_error() } diff --git a/examples/rust_pubsub/src/simple_subscriber.rs b/examples/rust_pubsub/src/simple_subscriber.rs index acda1aeaf..e9dc9a15a 100644 --- a/examples/rust_pubsub/src/simple_subscriber.rs +++ b/examples/rust_pubsub/src/simple_subscriber.rs @@ -7,7 +7,7 @@ use std::{ use std_msgs::msg::String as StringMsg; pub struct SimpleSubscriptionNode { - _subscriber: Arc>, + _subscriber: Subscription, data: Arc>>, } @@ -34,11 +34,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 subscription = SimpleSubscriptionNode::new(&executor).unwrap(); thread::spawn(move || loop { thread::sleep(Duration::from_millis(1000)); - subscription_other_thread.data_callback().unwrap() + subscription.data_callback().unwrap() }); executor.spin(SpinOptions::default()).first_error() } diff --git a/rclrs/src/client.rs b/rclrs/src/client.rs index f02e44e75..cf80b043a 100644 --- a/rclrs/src/client.rs +++ b/rclrs/src/client.rs @@ -65,12 +65,25 @@ type RequestId = i64; /// 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, { @@ -80,16 +93,16 @@ where /// Ensure the parent node remains alive as long as the subscription is held. /// This implementation will change in the future. #[allow(unused)] - node: Arc, + node: Node, } -impl Client +impl ClientState where T: rosidl_runtime_rs::Service, { /// Creates a new client. pub(crate) fn new<'a>( - node: &Arc, + node: &Node, options: impl Into>, ) -> Result // This uses pub(crate) visibility to avoid instantiating this struct outside @@ -319,7 +332,7 @@ impl<'a, T: IntoPrimitiveOptions<'a>> From for ClientOptions<'a> { } } -impl ClientBase for Client +impl ClientBase for ClientState where T: rosidl_runtime_rs::Service, { diff --git a/rclrs/src/executor.rs b/rclrs/src/executor.rs index 7ffb08c93..f38eec5bf 100644 --- a/rclrs/src/executor.rs +++ b/rclrs/src/executor.rs @@ -1,6 +1,6 @@ use crate::{ - rcl_bindings::rcl_context_is_valid, Context, ContextHandle, IntoNodeOptions, Node, RclrsError, - WaitSet, + rcl_bindings::rcl_context_is_valid, Context, ContextHandle, IntoNodeOptions, Node, NodeState, + RclrsError, WaitSet, }; use std::{ sync::{Arc, Mutex, Weak}, @@ -10,7 +10,7 @@ use std::{ /// Single-threaded executor implementation. pub struct Executor { context: Arc, - nodes_mtx: Mutex>>, + nodes_mtx: Mutex>>, } impl Executor { @@ -18,7 +18,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.context)?; self.nodes_mtx.lock().unwrap().push(Arc::downgrade(&node)); diff --git a/rclrs/src/node.rs b/rclrs/src/node.rs index 6e7dc597c..b2b734dee 100644 --- a/rclrs/src/node.rs +++ b/rclrs/src/node.rs @@ -19,11 +19,11 @@ use std::{ use rosidl_runtime_rs::Message; use crate::{ - rcl_bindings::*, Client, ClientBase, ClientOptions, Clock, ContextHandle, GuardCondition, - LogParams, Logger, ParameterBuilder, ParameterInterface, ParameterVariant, Parameters, - Publisher, PublisherOptions, RclrsError, Service, ServiceBase, ServiceOptions, Subscription, - SubscriptionBase, SubscriptionCallback, SubscriptionOptions, TimeSource, ToLogParams, - ENTITY_LIFECYCLE_MUTEX, + rcl_bindings::*, Client, ClientBase, ClientOptions, ClientState, Clock, ContextHandle, + GuardCondition, LogParams, Logger, ParameterBuilder, ParameterInterface, ParameterVariant, + Parameters, Publisher, PublisherOptions, PublisherState, RclrsError, Service, ServiceBase, + ServiceOptions, ServiceState, Subscription, SubscriptionBase, SubscriptionCallback, + SubscriptionOptions, SubscriptionState, TimeSource, ToLogParams, ENTITY_LIFECYCLE_MUTEX, }; // SAFETY: The functions accessing this type, including drop(), shouldn't care about the thread @@ -59,7 +59,7 @@ unsafe impl Send for rcl_node_t {} /// In that sense, the parameters to the node creation functions are only the _default_ namespace and /// name. /// See also the [official tutorial][1] on the command line arguments for ROS nodes, and the -/// [`Node::namespace()`][3] and [`Node::name()`][4] functions for examples. +/// [`NodeState::namespace()`] and [`NodeState::name()`] functions for examples. /// /// ## Rules for valid names /// The rules for valid node names and node namespaces are explained in @@ -72,7 +72,17 @@ unsafe impl Send for rcl_node_t {} /// [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`] +/// is provided as convenience alias for that. +/// +/// The public API of the [`Node`] type is implemented via `NodeState`. +pub struct NodeState { pub(crate) clients_mtx: Mutex>>, pub(crate) guard_conditions_mtx: Mutex>>, pub(crate) services_mtx: Mutex>>, @@ -128,15 +138,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()) @@ -144,7 +154,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() @@ -202,7 +212,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 /// ``` @@ -266,11 +276,11 @@ impl Node { pub fn create_client<'a, T>( self: &Arc, options: impl Into>, - ) -> Result>, RclrsError> + ) -> Result, RclrsError> where T: rosidl_runtime_rs::Service, { - let client = Arc::new(Client::::new(self, options)?); + let client = Arc::new(ClientState::::new(self, options)?); { self.clients_mtx.lock().unwrap() }.push(Arc::downgrade(&client) as Weak); Ok(client) } @@ -349,11 +359,11 @@ impl Node { pub fn create_publisher<'a, T>( &self, options: impl Into>, - ) -> Result>, RclrsError> + ) -> Result, RclrsError> where T: Message, { - let publisher = Arc::new(Publisher::::new(Arc::clone(&self.handle), options)?); + let publisher = Arc::new(PublisherState::::new(Arc::clone(&self.handle), options)?); Ok(publisher) } @@ -403,12 +413,12 @@ impl Node { self: &Arc, options: impl Into>, callback: F, - ) -> Result>, RclrsError> + ) -> Result, RclrsError> where T: rosidl_runtime_rs::Service, F: Fn(&rmw_request_id_t, T::Request) -> T::Response + 'static + Send, { - let service = Arc::new(Service::::new(self, options, callback)?); + let service = Arc::new(ServiceState::::new(self, options, callback)?); { self.services_mtx.lock().unwrap() } .push(Arc::downgrade(&service) as Weak); Ok(service) @@ -459,11 +469,11 @@ impl Node { self: &Arc, options: impl Into>, callback: impl SubscriptionCallback, - ) -> Result>, RclrsError> + ) -> Result, RclrsError> where T: Message, { - let subscription = Arc::new(Subscription::::new(self, options, callback)?); + let subscription = Arc::new(SubscriptionState::::new(self, options, callback)?); { self.subscriptions_mtx.lock() } .unwrap() .push(Arc::downgrade(&subscription) as Weak); @@ -583,7 +593,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 34419cccd..ff0dc0985 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 9f5a41581..4744a4812 100644 --- a/rclrs/src/node/node_options.rs +++ b/rclrs/src/node/node_options.rs @@ -5,8 +5,9 @@ use std::{ }; use crate::{ - rcl_bindings::*, ClockType, ContextHandle, Logger, Node, NodeHandle, ParameterInterface, - QoSProfile, RclrsError, TimeSource, ToResult, ENTITY_LIFECYCLE_MUTEX, QOS_PROFILE_CLOCK, + rcl_bindings::*, ClockType, ContextHandle, 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 @@ -285,7 +286,7 @@ impl<'a> NodeOptions<'a> { /// /// Only used internally. Downstream users should call /// [`Executor::create_node`]. - pub(crate) fn build(self, context: &Arc) -> Result, RclrsError> { + pub(crate) fn build(self, context: &Arc) -> Result { let node_name = CString::new(self.name).map_err(|err| RclrsError::StringContainsNul { err, s: self.name.to_owned(), @@ -355,7 +356,7 @@ impl<'a> NodeOptions<'a> { } }; - let node = Arc::new(Node { + let node = Arc::new(NodeState { clients_mtx: Mutex::default(), guard_conditions_mtx: Mutex::default(), services_mtx: Mutex::default(), diff --git a/rclrs/src/parameter.rs b/rclrs/src/parameter.rs index 083735eda..3a9f026da 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, @@ -789,7 +789,7 @@ impl ParameterInterface { } } - pub(crate) fn create_services(&self, node: &Arc) -> Result<(), RclrsError> { + pub(crate) fn create_services(&self, node: &Node) -> Result<(), RclrsError> { *self.services.lock().unwrap() = Some(ParameterService::new(node, self.parameter_map.clone())?); Ok(()) diff --git a/rclrs/src/parameter/service.rs b/rclrs/src/parameter/service.rs index 329170548..ad22f2c75 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( @@ -239,7 +239,7 @@ fn set_parameters_atomically( impl ParameterService { pub(crate) fn new( - node: &Arc, + node: &Node, parameter_map: Arc>, ) -> Result { let fqn = node.fully_qualified_name(); @@ -322,7 +322,7 @@ mod tests { }; struct TestNode { - node: Arc, + node: Node, bool_param: MandatoryParameter, _ns_param: MandatoryParameter, _read_only_param: ReadOnlyParameter, @@ -344,7 +344,7 @@ mod tests { Ok(()) } - 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 d92184cd0..7deb0111a 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][1]. /// -/// [1]: crate::Executor::spin -pub struct Publisher +/// [1]: crate::NodeState::create_publisher +/// [2]: crate::spin +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, { @@ -193,7 +210,7 @@ where } } -impl Publisher +impl PublisherState where T: RmwMessage, { @@ -282,7 +299,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 56ffae04c..120b2aa69 100644 --- a/rclrs/src/service.rs +++ b/rclrs/src/service.rs @@ -60,14 +60,33 @@ pub trait ServiceBase: Send + Sync { type ServiceCallback = Box Response + 'static + Send>; -/// Main class responsible for responding to requests sent by ROS clients. +/// Provide a service that can respond to requests sent by ROS service clients. /// -/// The only available way to instantiate services is via [`Node::create_service()`][1], this is to -/// ensure that [`Node`][2]s can track all the services that have been created. +/// Create a service using [`Node::create_service`][1]. /// -/// [1]: crate::Node::create_service -/// [2]: crate::Node -pub struct Service +/// 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][2]. +/// +/// [1]: crate::NodeState::create_service +/// [2]: crate::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, { @@ -77,16 +96,16 @@ where /// Ensure the parent node remains alive as long as the subscription is held. /// This implementation will change in the future. #[allow(unused)] - node: Arc, + node: Node, } -impl Service +impl ServiceState where T: rosidl_runtime_rs::Service, { /// Creates a new service. pub(crate) fn new<'a, F>( - node: &Arc, + node: &Node, options: impl Into>, callback: F, ) -> Result @@ -219,7 +238,7 @@ impl<'a, T: IntoPrimitiveOptions<'a>> From for ServiceOptions<'a> { } } -impl ServiceBase for Service +impl ServiceBase for ServiceState where T: rosidl_runtime_rs::Service, { diff --git a/rclrs/src/subscription.rs b/rclrs/src/subscription.rs index d015aad43..70afe320e 100644 --- a/rclrs/src/subscription.rs +++ b/rclrs/src/subscription.rs @@ -64,20 +64,32 @@ pub trait SubscriptionBase: Send + Sync { /// Struct for receiving messages of type `T`. /// +/// Create a subscription using [`Node::create_subscription`][1]. +/// /// 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 the node's executor to [spin][2]. /// /// When a subscription is created, it may take some time to get "matched" with a corresponding /// publisher. /// -/// The only available way to instantiate subscriptions is via [`Node::create_subscription()`][3], this -/// is to ensure that [`Node`][4]s can track all the subscriptions that have been created. +/// [1]: crate::NodeState::create_subscription +/// [2]: crate::spin +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`. /// -/// [2]: crate::Executor::spin -/// [3]: crate::Node::create_subscription -/// [4]: crate::Node -pub struct Subscription +/// [1]: std::sync::Weak +pub struct SubscriptionState where T: Message, { @@ -87,17 +99,17 @@ where /// Ensure the parent node remains alive as long as the subscription is held. /// This implementation will change in the future. #[allow(unused)] - node: Arc, + node: Node, message: PhantomData, } -impl Subscription +impl SubscriptionState where T: Message, { /// Creates a new subscription. pub(crate) fn new<'a, Args>( - node: &Arc, + node: &Node, options: impl Into>, callback: impl SubscriptionCallback, ) -> Result @@ -237,11 +249,11 @@ where /// When there is no new message, this will return a /// [`SubscriptionTakeFailed`][1]. /// - /// This is the counterpart to [`Publisher::borrow_loaned_message()`][2]. See its documentation + /// This is the counterpart to [`PublisherState::borrow_loaned_message()`][2]. See its documentation /// for more information. /// /// [1]: crate::RclrsError - /// [2]: crate::Publisher::borrow_loaned_message + /// [2]: crate::PublisherState::borrow_loaned_message pub fn take_loaned(&self) -> Result<(ReadOnlyLoanedMessage<'_, T>, MessageInfo), RclrsError> { let mut msg_ptr = std::ptr::null_mut(); let mut message_info = unsafe { rmw_get_zero_initialized_message_info() }; @@ -299,7 +311,7 @@ impl<'a, T: IntoPrimitiveOptions<'a>> From for SubscriptionOptions<'a> { } } -impl SubscriptionBase for Subscription +impl SubscriptionBase for SubscriptionState where T: Message, { @@ -362,8 +374,8 @@ mod tests { #[test] fn traits() { - assert_send::>(); - assert_sync::>(); + assert_send::>(); + assert_sync::>(); } #[test] diff --git a/rclrs/src/subscription/readonly_loaned_message.rs b/rclrs/src/subscription/readonly_loaned_message.rs index c6f52e280..3c7212ccc 100644 --- a/rclrs/src/subscription/readonly_loaned_message.rs +++ b/rclrs/src/subscription/readonly_loaned_message.rs @@ -2,7 +2,7 @@ use std::ops::Deref; use rosidl_runtime_rs::Message; -use crate::{rcl_bindings::*, Subscription, ToResult}; +use crate::{rcl_bindings::*, SubscriptionState, ToResult}; /// A message that is owned by the middleware, loaned out for reading. /// @@ -10,7 +10,7 @@ use crate::{rcl_bindings::*, Subscription, ToResult}; /// message, it's the same as `&T`, and otherwise it's the corresponding RMW-native /// message. /// -/// This type is returned by [`Subscription::take_loaned()`] and may be used in +/// This type is returned by [`SubscriptionState::take_loaned()`] and may be used in /// subscription callbacks. /// /// The loan is returned by dropping the `ReadOnlyLoanedMessage`. @@ -19,7 +19,7 @@ where T: Message, { pub(super) msg_ptr: *const T::RmwMsg, - pub(super) subscription: &'a Subscription, + pub(super) subscription: &'a SubscriptionState, } impl Deref for ReadOnlyLoanedMessage<'_, T> diff --git a/rclrs/src/test_helpers/graph_helpers.rs b/rclrs/src/test_helpers/graph_helpers.rs index 838ef49f9..0a5ccbff4 100644 --- a/rclrs/src/test_helpers/graph_helpers.rs +++ b/rclrs/src/test_helpers/graph_helpers.rs @@ -1,9 +1,8 @@ use crate::*; -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 88476de76..bb2c52fd8 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