Skip to content

Commit bbb5333

Browse files
committed
Migrate primitives to state pattern
Signed-off-by: Michael X. Grey <[email protected]>
1 parent bf3d01a commit bbb5333

File tree

9 files changed

+125
-65
lines changed

9 files changed

+125
-65
lines changed

rclrs/src/client.rs

Lines changed: 19 additions & 6 deletions
Original file line numberDiff line numberDiff line change
@@ -64,12 +64,25 @@ type RequestId = i64;
6464

6565
/// Main class responsible for sending requests to a ROS service.
6666
///
67-
/// The only available way to instantiate clients is via [`Node::create_client`][1], this is to
68-
/// ensure that [`Node`][2]s can track all the clients that have been created.
67+
/// Create a client using [`Node::create_client`][1].
68+
///
69+
/// Receiving responses requires the node's executor to [spin][2].
6970
///
7071
/// [1]: crate::NodeState::create_client
71-
/// [2]: crate::Node
72-
pub struct Client<T>
72+
/// [2]: crate::spin
73+
pub type Client<T> = Arc<ClientState<T>>;
74+
75+
/// The inner state of a [`Client`].
76+
///
77+
/// This is public so that you can choose to create a [`Weak`][1] reference to it
78+
/// if you want to be able to refer to a [`Client`] in a non-owning way. It is
79+
/// generally recommended to manage the `ClientState` inside of an [`Arc`],
80+
/// and [`Client`] is provided as a convenience alias for that.
81+
///
82+
/// The public API of the [`Client`] type is implemented via `ClientState`.
83+
///
84+
/// [1]: std::sync::Weak
85+
pub struct ClientState<T>
7386
where
7487
T: rosidl_runtime_rs::Service,
7588
{
@@ -78,7 +91,7 @@ where
7891
futures: Arc<Mutex<HashMap<RequestId, oneshot::Sender<T::Response>>>>,
7992
}
8093

81-
impl<T> Client<T>
94+
impl<T> ClientState<T>
8295
where
8396
T: rosidl_runtime_rs::Service,
8497
{
@@ -275,7 +288,7 @@ where
275288
}
276289
}
277290

278-
impl<T> ClientBase for Client<T>
291+
impl<T> ClientBase for ClientState<T>
279292
where
280293
T: rosidl_runtime_rs::Service,
281294
{

rclrs/src/node.rs

Lines changed: 16 additions & 16 deletions
Original file line numberDiff line numberDiff line change
@@ -13,10 +13,10 @@ use rosidl_runtime_rs::Message;
1313

1414
pub use self::{builder::*, graph::*};
1515
use crate::{
16-
rcl_bindings::*, Client, ClientBase, Clock, Context, ContextHandle, GuardCondition,
17-
ParameterBuilder, ParameterInterface, ParameterVariant, Parameters, Publisher, QoSProfile,
18-
RclrsError, Service, ServiceBase, Subscription, SubscriptionBase, SubscriptionCallback,
19-
TimeSource, ENTITY_LIFECYCLE_MUTEX,
16+
rcl_bindings::*, Client, ClientBase, ClientState, Clock, Context, ContextHandle,
17+
GuardCondition, ParameterBuilder, ParameterInterface, ParameterVariant, Parameters, Publisher,
18+
PublisherState, QoSProfile, RclrsError, Service, ServiceBase, ServiceState, Subscription,
19+
SubscriptionBase, SubscriptionCallback, SubscriptionState, TimeSource, ENTITY_LIFECYCLE_MUTEX,
2020
};
2121

2222
// SAFETY: The functions accessing this type, including drop(), shouldn't care about the thread
@@ -212,11 +212,11 @@ impl NodeState {
212212
///
213213
/// [1]: crate::Client
214214
// TODO: make client's lifetime depend on node's lifetime
215-
pub fn create_client<T>(&self, topic: &str) -> Result<Arc<Client<T>>, RclrsError>
215+
pub fn create_client<T>(&self, topic: &str) -> Result<Client<T>, RclrsError>
216216
where
217217
T: rosidl_runtime_rs::Service,
218218
{
219-
let client = Arc::new(Client::<T>::new(Arc::clone(&self.handle), topic)?);
219+
let client = Arc::new(ClientState::<T>::new(Arc::clone(&self.handle), topic)?);
220220
{ self.clients_mtx.lock().unwrap() }.push(Arc::downgrade(&client) as Weak<dyn ClientBase>);
221221
Ok(client)
222222
}
@@ -270,28 +270,28 @@ impl NodeState {
270270
&self,
271271
topic: &str,
272272
qos: QoSProfile,
273-
) -> Result<Arc<Publisher<T>>, RclrsError>
273+
) -> Result<Publisher<T>, RclrsError>
274274
where
275275
T: Message,
276276
{
277-
let publisher = Arc::new(Publisher::<T>::new(Arc::clone(&self.handle), topic, qos)?);
277+
let publisher = Arc::new(PublisherState::<T>::new(
278+
Arc::clone(&self.handle),
279+
topic,
280+
qos,
281+
)?);
278282
Ok(publisher)
279283
}
280284

281285
/// Creates a [`Service`][1].
282286
///
283287
/// [1]: crate::Service
284288
// TODO: make service's lifetime depend on node's lifetime
285-
pub fn create_service<T, F>(
286-
&self,
287-
topic: &str,
288-
callback: F,
289-
) -> Result<Arc<Service<T>>, RclrsError>
289+
pub fn create_service<T, F>(&self, topic: &str, callback: F) -> Result<Service<T>, RclrsError>
290290
where
291291
T: rosidl_runtime_rs::Service,
292292
F: Fn(&rmw_request_id_t, T::Request) -> T::Response + 'static + Send,
293293
{
294-
let service = Arc::new(Service::<T>::new(
294+
let service = Arc::new(ServiceState::<T>::new(
295295
Arc::clone(&self.handle),
296296
topic,
297297
callback,
@@ -310,11 +310,11 @@ impl NodeState {
310310
topic: &str,
311311
qos: QoSProfile,
312312
callback: impl SubscriptionCallback<T, Args>,
313-
) -> Result<Arc<Subscription<T>>, RclrsError>
313+
) -> Result<Subscription<T>, RclrsError>
314314
where
315315
T: Message,
316316
{
317-
let subscription = Arc::new(Subscription::<T>::new(
317+
let subscription = Arc::new(SubscriptionState::<T>::new(
318318
Arc::clone(&self.handle),
319319
topic,
320320
qos,

rclrs/src/parameter/service.rs

Lines changed: 6 additions & 6 deletions
Original file line numberDiff line numberDiff line change
@@ -16,17 +16,17 @@ use crate::{
1616
// What is used is the Weak that is stored in the node, and is upgraded when spinning.
1717
pub struct ParameterService {
1818
#[allow(dead_code)]
19-
describe_parameters_service: Arc<Service<DescribeParameters>>,
19+
describe_parameters_service: Service<DescribeParameters>,
2020
#[allow(dead_code)]
21-
get_parameter_types_service: Arc<Service<GetParameterTypes>>,
21+
get_parameter_types_service: Service<GetParameterTypes>,
2222
#[allow(dead_code)]
23-
get_parameters_service: Arc<Service<GetParameters>>,
23+
get_parameters_service: Service<GetParameters>,
2424
#[allow(dead_code)]
25-
list_parameters_service: Arc<Service<ListParameters>>,
25+
list_parameters_service: Service<ListParameters>,
2626
#[allow(dead_code)]
27-
set_parameters_service: Arc<Service<SetParameters>>,
27+
set_parameters_service: Service<SetParameters>,
2828
#[allow(dead_code)]
29-
set_parameters_atomically_service: Arc<Service<SetParametersAtomically>>,
29+
set_parameters_atomically_service: Service<SetParametersAtomically>,
3030
}
3131

3232
fn describe_parameters(

rclrs/src/publisher.rs

Lines changed: 25 additions & 8 deletions
Original file line numberDiff line numberDiff line change
@@ -45,15 +45,32 @@ impl Drop for PublisherHandle {
4545

4646
/// Struct for sending messages of type `T`.
4747
///
48+
/// Create a publisher using [`Node::create_publisher`][1].
49+
///
4850
/// Multiple publishers can be created for the same topic, in different nodes or the same node.
51+
/// A clone of a `Publisher` will refer to the same publisher instance as the original.
52+
/// The underlying instance is tied to [`PublisherState`] which implements the [`Publisher`] API.
4953
///
5054
/// The underlying RMW will decide on the concrete delivery mechanism (network stack, shared
5155
/// memory, or intraprocess).
5256
///
53-
/// Sending messages does not require calling [`spin`][1] on the publisher's node.
57+
/// Sending messages does not require calling [`spin`][2] on the publisher's node.
58+
///
59+
/// [1]: crate::NodeState::create_publisher
60+
/// [2]: crate::spin
61+
pub type Publisher<T> = Arc<PublisherState<T>>;
62+
63+
/// The inner state of a [`Publisher`].
64+
///
65+
/// This is public so that you can choose to create a [`Weak`][1] reference to it
66+
/// if you want to be able to refer to a [`Publisher`] in a non-owning way. It is
67+
/// generally recommended to manage the `PublisherState` inside of an [`Arc`],
68+
/// and [`Publisher`] is provided as a convenience alias for that.
69+
///
70+
/// The public API of the [`Publisher`] type is implemented via `PublisherState`.
5471
///
55-
/// [1]: crate::spin
56-
pub struct Publisher<T>
72+
/// [1]: std::sync::Weak
73+
pub struct PublisherState<T>
5774
where
5875
T: Message,
5976
{
@@ -66,12 +83,12 @@ where
6683

6784
// SAFETY: The functions accessing this type, including drop(), shouldn't care about the thread
6885
// they are running in. Therefore, this type can be safely sent to another thread.
69-
unsafe impl<T> Send for Publisher<T> where T: Message {}
86+
unsafe impl<T> Send for PublisherState<T> where T: Message {}
7087
// SAFETY: The type_support_ptr prevents the default Sync impl.
7188
// rosidl_message_type_support_t is a read-only type without interior mutability.
72-
unsafe impl<T> Sync for Publisher<T> where T: Message {}
89+
unsafe impl<T> Sync for PublisherState<T> where T: Message {}
7390

74-
impl<T> Publisher<T>
91+
impl<T> PublisherState<T>
7592
where
7693
T: Message,
7794
{
@@ -179,7 +196,7 @@ where
179196
}
180197
}
181198

182-
impl<T> Publisher<T>
199+
impl<T> PublisherState<T>
183200
where
184201
T: RmwMessage,
185202
{
@@ -231,7 +248,7 @@ where
231248
}
232249
}
233250

234-
/// Convenience trait for [`Publisher::publish`].
251+
/// Convenience trait for [`PublisherState::publish`].
235252
pub trait MessageCow<'a, T: Message> {
236253
/// Wrap the owned or borrowed message in a `Cow`.
237254
fn into_cow(self) -> Cow<'a, T>;

rclrs/src/publisher/loaned_message.rs

Lines changed: 3 additions & 3 deletions
Original file line numberDiff line numberDiff line change
@@ -2,13 +2,13 @@ use std::ops::{Deref, DerefMut};
22

33
use rosidl_runtime_rs::RmwMessage;
44

5-
use crate::{rcl_bindings::*, Publisher, RclrsError, ToResult};
5+
use crate::{rcl_bindings::*, PublisherState, RclrsError, ToResult};
66

77
/// A message that is owned by the middleware, loaned for publishing.
88
///
99
/// It dereferences to a `&mut T`.
1010
///
11-
/// This type is returned by [`Publisher::borrow_loaned_message()`], see the documentation of
11+
/// This type is returned by [`PublisherState::borrow_loaned_message()`], see the documentation of
1212
/// that function for more information.
1313
///
1414
/// The loan is returned by dropping the message or [publishing it][1].
@@ -19,7 +19,7 @@ where
1919
T: RmwMessage,
2020
{
2121
pub(super) msg_ptr: *mut T,
22-
pub(super) publisher: &'a Publisher<T>,
22+
pub(super) publisher: &'a PublisherState<T>,
2323
}
2424

2525
impl<'a, T> Deref for LoanedMessage<'a, T>

rclrs/src/service.rs

Lines changed: 26 additions & 7 deletions
Original file line numberDiff line numberDiff line change
@@ -59,14 +59,33 @@ pub trait ServiceBase: Send + Sync {
5959
type ServiceCallback<Request, Response> =
6060
Box<dyn Fn(&rmw_request_id_t, Request) -> Response + 'static + Send>;
6161

62-
/// Main class responsible for responding to requests sent by ROS clients.
62+
/// Provide a service that can respond to requests sent by ROS service clients.
6363
///
64-
/// The only available way to instantiate services is via [`Node::create_service()`][1], this is to
65-
/// ensure that [`Node`][2]s can track all the services that have been created.
64+
/// Create a service using [`Node::create_service`][1].
65+
///
66+
/// ROS only supports having one service provider for any given fully-qualified
67+
/// service name. "Fully-qualified" means the namespace is also taken into account
68+
/// for uniqueness. A clone of a `Service` will refer to the same service provider
69+
/// instance as the original. The underlying instance is tied to [`ServiceState`]
70+
/// which implements the [`Service`] API.
71+
///
72+
/// Responding to requests requires the node's executor to [spin][2].
6673
///
6774
/// [1]: crate::NodeState::create_service
68-
/// [2]: crate::Node
69-
pub struct Service<T>
75+
/// [2]: crate::spin
76+
pub type Service<T> = Arc<ServiceState<T>>;
77+
78+
/// The inner state of a [`Service`].
79+
///
80+
/// This is public so that you can choose to create a [`Weak`][1] reference to it
81+
/// if you want to be able to refer to a [`Service`] in a non-owning way. It is
82+
/// generally recommended to manage the `ServiceState` inside of an [`Arc`],
83+
/// and [`Service`] is provided as a convenience alias for that.
84+
///
85+
/// The public API of the [`Service`] type is implemented via `ServiceState`.
86+
///
87+
/// [1]: std::sync::Weak
88+
pub struct ServiceState<T>
7089
where
7190
T: rosidl_runtime_rs::Service,
7291
{
@@ -75,7 +94,7 @@ where
7594
pub callback: Mutex<ServiceCallback<T::Request, T::Response>>,
7695
}
7796

78-
impl<T> Service<T>
97+
impl<T> ServiceState<T>
7998
where
8099
T: rosidl_runtime_rs::Service,
81100
{
@@ -181,7 +200,7 @@ where
181200
}
182201
}
183202

184-
impl<T> ServiceBase for Service<T>
203+
impl<T> ServiceBase for ServiceState<T>
185204
where
186205
T: rosidl_runtime_rs::Service,
187206
{

rclrs/src/subscription.rs

Lines changed: 25 additions & 14 deletions
Original file line numberDiff line numberDiff line change
@@ -64,21 +64,32 @@ pub trait SubscriptionBase: Send + Sync {
6464

6565
/// Struct for receiving messages of type `T`.
6666
///
67+
/// Create a subscription using [`Node::create_subscription`][1].
68+
///
6769
/// There can be multiple subscriptions for the same topic, in different nodes or the same node.
70+
/// A clone of a `Subscription` will refer to the same subscription instance as the original.
71+
/// The underlying instance is tied to [`SubscriptionState`] which implements the [`Subscription`] API.
6872
///
69-
/// Receiving messages requires calling [`spin_once`][1] or [`spin`][2] on the subscription's node.
73+
/// Receiving messages requires the node's executor to [spin][2].
7074
///
7175
/// When a subscription is created, it may take some time to get "matched" with a corresponding
7276
/// publisher.
7377
///
74-
/// The only available way to instantiate subscriptions is via [`Node::create_subscription()`][3], this
75-
/// is to ensure that [`Node`][4]s can track all the subscriptions that have been created.
76-
///
77-
/// [1]: crate::spin_once
78+
/// [1]: crate::NodeState::create_subscription
7879
/// [2]: crate::spin
79-
/// [3]: crate::NodeState::create_subscription
80-
/// [4]: crate::Node
81-
pub struct Subscription<T>
80+
pub type Subscription<T> = Arc<SubscriptionState<T>>;
81+
82+
/// The inner state of a [`Subscription`].
83+
///
84+
/// This is public so that you can choose to create a [`Weak`][1] reference to it
85+
/// if you want to be able to refer to a [`Subscription`] in a non-owning way. It is
86+
/// generally recommended to manage the `SubscriptionState` inside of an [`Arc`],
87+
/// and [`Subscription`] is provided as a convenience alias for that.
88+
///
89+
/// The public API of the [`Subscription`] type is implemented via `SubscriptionState`.
90+
///
91+
/// [1]: std::sync::Weak
92+
pub struct SubscriptionState<T>
8293
where
8394
T: Message,
8495
{
@@ -88,7 +99,7 @@ where
8899
message: PhantomData<T>,
89100
}
90101

91-
impl<T> Subscription<T>
102+
impl<T> SubscriptionState<T>
92103
where
93104
T: Message,
94105
{
@@ -233,11 +244,11 @@ where
233244
/// When there is no new message, this will return a
234245
/// [`SubscriptionTakeFailed`][1].
235246
///
236-
/// This is the counterpart to [`Publisher::borrow_loaned_message()`][2]. See its documentation
247+
/// This is the counterpart to [`PublisherState::borrow_loaned_message()`][2]. See its documentation
237248
/// for more information.
238249
///
239250
/// [1]: crate::RclrsError
240-
/// [2]: crate::Publisher::borrow_loaned_message
251+
/// [2]: crate::PublisherState::borrow_loaned_message
241252
pub fn take_loaned(&self) -> Result<(ReadOnlyLoanedMessage<'_, T>, MessageInfo), RclrsError> {
242253
let mut msg_ptr = std::ptr::null_mut();
243254
let mut message_info = unsafe { rmw_get_zero_initialized_message_info() };
@@ -263,7 +274,7 @@ where
263274
}
264275
}
265276

266-
impl<T> SubscriptionBase for Subscription<T>
277+
impl<T> SubscriptionBase for SubscriptionState<T>
267278
where
268279
T: Message,
269280
{
@@ -326,8 +337,8 @@ mod tests {
326337

327338
#[test]
328339
fn traits() {
329-
assert_send::<Subscription<msg::BoundedSequences>>();
330-
assert_sync::<Subscription<msg::BoundedSequences>>();
340+
assert_send::<SubscriptionState<msg::BoundedSequences>>();
341+
assert_sync::<SubscriptionState<msg::BoundedSequences>>();
331342
}
332343

333344
#[test]

0 commit comments

Comments
 (0)